ed_sensor_integration
Public Member Functions | Private Attributes | List of all members
Segmenter Class Reference

#include <segmenter.h>

Public Member Functions

void calculatePointsWithin (const rgbd::Image &image, const geo::Shape &shape, const geo::Pose3D &shape_pose, cv::Mat &filtered_depth_image) const
 
std::vector< cv::Mat > cluster (const cv::Mat &depth_image, const geo::DepthCamera &cam_model, const geo::Pose3D &sensor_pose, std::vector< EntityUpdate > &clusters, const cv::Mat &rgb_image, bool logging=false)
 Cluster the depth image into segments. Applies new algorithm which is the YOLO - SAM - BMM depth segmentation pipeline. More...
 
cv::Mat preprocessRGBForSegmentation (const cv::Mat &rgb_image, const cv::Mat &filtered_depth_image) const
 Preprocess RGB image for segmentation. This function masks the RGB image with the filtered depth image (non-zero depth values are kept) It returns a masked RGB image with values only where depth is non-zero. More...
 
void removeBackground (cv::Mat &depth_image, const ed::WorldModel &world, const geo::DepthCamera &cam, const geo::Pose3D &sensor_pose, double background_padding)
 
 Segmenter (tue::Configuration config)
 
 ~Segmenter ()
 

Private Attributes

tue::Configuration config_
 

Detailed Description

Definition at line 28 of file segmenter.h.

Constructor & Destructor Documentation

◆ Segmenter()

Segmenter::Segmenter ( tue::Configuration  config)

Definition at line 31 of file src/kinect/segmenter.cpp.

◆ ~Segmenter()

Segmenter::~Segmenter ( )

Definition at line 38 of file src/kinect/segmenter.cpp.

Member Function Documentation

◆ calculatePointsWithin()

void Segmenter::calculatePointsWithin ( const rgbd::Image image,
const geo::Shape shape,
const geo::Pose3D shape_pose,
cv::Mat &  filtered_depth_image 
) const

Definition at line 147 of file src/kinect/segmenter.cpp.

◆ cluster()

std::vector< cv::Mat > Segmenter::cluster ( const cv::Mat &  depth_image,
const geo::DepthCamera cam_model,
const geo::Pose3D sensor_pose,
std::vector< EntityUpdate > &  clusters,
const cv::Mat &  rgb_image,
bool  logging = false 
)

Cluster the depth image into segments. Applies new algorithm which is the YOLO - SAM - BMM depth segmentation pipeline.

Parameters
depth_image
cam_model
sensor_pose
clusters
rgb_image
Returns
std::vector<cv::Mat> masks // 3D pointcloud masks of all the segmented objects

Definition at line 202 of file src/kinect/segmenter.cpp.

◆ preprocessRGBForSegmentation()

cv::Mat Segmenter::preprocessRGBForSegmentation ( const cv::Mat &  rgb_image,
const cv::Mat &  filtered_depth_image 
) const

Preprocess RGB image for segmentation. This function masks the RGB image with the filtered depth image (non-zero depth values are kept) It returns a masked RGB image with values only where depth is non-zero.

Parameters
rgb_image
filtered_depth_image
Returns
cv::Mat filtered_depth_image

Definition at line 184 of file src/kinect/segmenter.cpp.

◆ removeBackground()

void Segmenter::removeBackground ( cv::Mat &  depth_image,
const ed::WorldModel world,
const geo::DepthCamera cam,
const geo::Pose3D sensor_pose,
double  background_padding 
)

Definition at line 77 of file src/kinect/segmenter.cpp.

Member Data Documentation

◆ config_

tue::Configuration Segmenter::config_
private

Definition at line 66 of file segmenter.h.


The documentation for this class was generated from the following files: