#include <depth_cloud_mld.h>
Public Member Functions | |
void | enableOcclusionCompensation (bool occlusion_compensation) |
sensor_msgs::PointCloud2Ptr | generatePointCloudFromDepth (sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImageConstPtr color_msg, sensor_msgs::CameraInfoConstPtr camera_info_msg) |
MultiLayerDepth () | |
void | reset () |
void | setShadowTimeOut (double time_out) |
virtual | ~MultiLayerDepth () |
Protected Member Functions | |
template<typename T > | |
void | convertColor (const sensor_msgs::ImageConstPtr &color_msg, std::vector< uint32_t > &rgba_color_raw) |
Convert color data to RGBA format. | |
void | finalizingPointCloud (sensor_msgs::PointCloud2Ptr &point_cloud, std::size_t size) |
template<typename T > | |
sensor_msgs::PointCloud2Ptr | generatePointCloudML (const sensor_msgs::ImageConstPtr &depth_msg, std::vector< uint32_t > &rgba_color_raw) |
Generate multi-layered depth cloud (depth+shadow) | |
template<typename T > | |
sensor_msgs::PointCloud2Ptr | generatePointCloudSL (const sensor_msgs::ImageConstPtr &depth_msg, std::vector< uint32_t > &rgba_color_raw) |
Generate single-layered depth cloud (depth only) | |
void | initializeConversion (const sensor_msgs::ImageConstPtr &depth_msg, sensor_msgs::CameraInfoConstPtr &camera_info_msg) |
Precompute projection matrix, initialize buffers. | |
sensor_msgs::PointCloud2Ptr | initPointCloud () |
Protected Attributes | |
bool | occlusion_compensation_ |
std::vector< float > | projection_map_x_ |
std::vector< float > | projection_map_y_ |
std::vector< uint8_t > | shadow_buffer_ |
std::vector< float > | shadow_depth_ |
float | shadow_distance_ |
double | shadow_time_out_ |
std::vector< double > | shadow_timestamp_ |
Definition at line 64 of file depth_cloud_mld.h.
rviz::MultiLayerDepth::MultiLayerDepth | ( | ) | [inline] |
Definition at line 67 of file depth_cloud_mld.h.
virtual rviz::MultiLayerDepth::~MultiLayerDepth | ( | ) | [inline, virtual] |
Definition at line 71 of file depth_cloud_mld.h.
void rviz::MultiLayerDepth::convertColor | ( | const sensor_msgs::ImageConstPtr & | color_msg, |
std::vector< uint32_t > & | rgba_color_raw | ||
) | [protected] |
Convert color data to RGBA format.
Definition at line 390 of file depth_cloud_mld.cpp.
void rviz::MultiLayerDepth::enableOcclusionCompensation | ( | bool | occlusion_compensation | ) | [inline] |
Definition at line 79 of file depth_cloud_mld.h.
void rviz::MultiLayerDepth::finalizingPointCloud | ( | sensor_msgs::PointCloud2Ptr & | point_cloud, |
std::size_t | size | ||
) | [protected] |
Definition at line 580 of file depth_cloud_mld.cpp.
sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::generatePointCloudFromDepth | ( | sensor_msgs::ImageConstPtr | depth_msg, |
sensor_msgs::ImageConstPtr | color_msg, | ||
sensor_msgs::CameraInfoConstPtr | camera_info_msg | ||
) |
Definition at line 453 of file depth_cloud_mld.cpp.
sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::generatePointCloudML | ( | const sensor_msgs::ImageConstPtr & | depth_msg, |
std::vector< uint32_t > & | rgba_color_raw | ||
) | [protected] |
Generate multi-layered depth cloud (depth+shadow)
Definition at line 256 of file depth_cloud_mld.cpp.
sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::generatePointCloudSL | ( | const sensor_msgs::ImageConstPtr & | depth_msg, |
std::vector< uint32_t > & | rgba_color_raw | ||
) | [protected] |
Generate single-layered depth cloud (depth only)
Definition at line 174 of file depth_cloud_mld.cpp.
void rviz::MultiLayerDepth::initializeConversion | ( | const sensor_msgs::ImageConstPtr & | depth_msg, |
sensor_msgs::CameraInfoConstPtr & | camera_info_msg | ||
) | [protected] |
Precompute projection matrix, initialize buffers.
Definition at line 91 of file depth_cloud_mld.cpp.
sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::initPointCloud | ( | ) | [protected] |
Definition at line 541 of file depth_cloud_mld.cpp.
void rviz::MultiLayerDepth::reset | ( | ) | [inline] |
Definition at line 88 of file depth_cloud_mld.h.
void rviz::MultiLayerDepth::setShadowTimeOut | ( | double | time_out | ) | [inline] |
Definition at line 74 of file depth_cloud_mld.h.
bool rviz::MultiLayerDepth::occlusion_compensation_ [protected] |
Definition at line 132 of file depth_cloud_mld.h.
std::vector<float> rviz::MultiLayerDepth::projection_map_x_ [protected] |
Definition at line 123 of file depth_cloud_mld.h.
std::vector<float> rviz::MultiLayerDepth::projection_map_y_ [protected] |
Definition at line 124 of file depth_cloud_mld.h.
std::vector< uint8_t > rviz::MultiLayerDepth::shadow_buffer_ [protected] |
Definition at line 129 of file depth_cloud_mld.h.
std::vector< float > rviz::MultiLayerDepth::shadow_depth_ [protected] |
Definition at line 127 of file depth_cloud_mld.h.
float rviz::MultiLayerDepth::shadow_distance_ [protected] |
Definition at line 134 of file depth_cloud_mld.h.
double rviz::MultiLayerDepth::shadow_time_out_ [protected] |
Definition at line 133 of file depth_cloud_mld.h.
std::vector< double > rviz::MultiLayerDepth::shadow_timestamp_ [protected] |
Definition at line 128 of file depth_cloud_mld.h.