ed_sensor_integration
Functions
sam_seg_module.h File Reference
#include <opencv2/core.hpp>
#include <geolib/datatypes.h>
#include <ros/publisher.h>
#include <tue/config/configuration.h>
#include "ed/kinect/entity_update.h"
#include <vector>
Include dependency graph for sam_seg_module.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Functions

void overlayMasksOnImage_ (cv::Mat &rgb, const std::vector< cv::Mat > &masks)
 Overlay segmentation masks on the RGB image for visualization purposes. More...
 
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. More...
 
std::vector< cv::Mat > SegmentationPipeline (const cv::Mat &img, tue::Configuration &config)
 Segmentation pipeline that processes the input image and generates segmentation masks. More...
 

Function Documentation

◆ overlayMasksOnImage_()

void overlayMasksOnImage_ ( cv::Mat &  rgb,
const std::vector< cv::Mat > &  masks 
)

Overlay segmentation masks on the RGB image for visualization purposes.

Parameters
rgbThe RGB image to overlay masks on.
masksThe segmentation masks to overlay.

Definition at line 59 of file sam_seg_module.cpp.

◆ 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.

Parameters
filtered_depth_imageThe filtered depth image to publish.
rgbThe RGB image to publish.
sensor_poseThe pose of the sensor.
clustered_imagesThe clustered segmentation masks.
mask_pub_The ROS publisher for the mask images.
cloud_pub_The ROS publisher for the point cloud data.
res_updatesThe entity updates to publish.

Definition at line 112 of file sam_seg_module.cpp.

◆ SegmentationPipeline()

std::vector<cv::Mat> SegmentationPipeline ( const cv::Mat &  img,
tue::Configuration config 
)

Segmentation pipeline that processes the input image and generates segmentation masks.

Parameters
imgThe input RGB image to segment.
Returns
std::vector<cv::Mat> The generated segmentation masks.

Definition at line 14 of file sam_seg_module.cpp.