ed_sensor_integration
sam_seg_module.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <opencv2/core.hpp>
4 
5 #include <geolib/datatypes.h>
6 #include <ros/publisher.h>
8 
10 
11 #include <vector>
12 
20 
27 void overlayMasksOnImage_(cv::Mat& rgb, const std::vector<cv::Mat>& masks);
28 
40 void publishSegmentationResults(const cv::Mat& filtered_depth_image, const cv::Mat& rgb,
41  const geo::Pose3D& sensor_pose, std::vector<cv::Mat>& clustered_images,
42  ros::Publisher& mask_pub_, ros::Publisher& cloud_pub_, std::vector<EntityUpdate>& res_updates);
datatypes.h
publishSegmentationResults
void publishSegmentationResults(const cv::Mat &filtered_depth_image, const cv::Mat &rgb, const geo::Pose3D &sensor_pose, std::vector< cv::Mat > &clustered_images, ros::Publisher &mask_pub_, ros::Publisher &cloud_pub_, std::vector< EntityUpdate > &res_updates)
Publish segmentation results and pointcloud estimation as ROS messages.
Definition: sam_seg_module.cpp:112
vector
geo::Transform3T
tue::config::ReaderWriter
configuration.h
entity_update.h
overlayMasksOnImage_
void overlayMasksOnImage_(cv::Mat &rgb, const std::vector< cv::Mat > &masks)
Overlay segmentation masks on the RGB image for visualization purposes.
Definition: sam_seg_module.cpp:59
SegmentationPipeline
std::vector< cv::Mat > SegmentationPipeline(const cv::Mat &img, tue::Configuration &config)
Segmentation pipeline that processes the input image and generates segmentation masks.
Definition: sam_seg_module.cpp:14