#include <depth_cloud_mld.h>
|
template<typename T > |
void | convertColor (const sensor_msgs::ImageConstPtr &color_msg, std::vector< uint32_t > &rgba_color_raw) |
| Convert color data to RGBA format. More...
|
|
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) More...
|
|
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) More...
|
|
void | initializeConversion (const sensor_msgs::ImageConstPtr &depth_msg, sensor_msgs::CameraInfoConstPtr &camera_info_msg) |
| Precompute projection matrix, initialize buffers. More...
|
|
sensor_msgs::PointCloud2Ptr | initPointCloud () |
|
Definition at line 64 of file depth_cloud_mld.h.
rviz::MultiLayerDepth::MultiLayerDepth |
( |
| ) |
|
|
inline |
virtual rviz::MultiLayerDepth::~MultiLayerDepth |
( |
| ) |
|
|
inlinevirtual |
template<typename T >
void rviz::MultiLayerDepth::convertColor |
( |
const sensor_msgs::ImageConstPtr & |
color_msg, |
|
|
std::vector< uint32_t > & |
rgba_color_raw |
|
) |
| |
|
protected |
void rviz::MultiLayerDepth::enableOcclusionCompensation |
( |
bool |
occlusion_compensation | ) |
|
|
inline |
void rviz::MultiLayerDepth::finalizingPointCloud |
( |
sensor_msgs::PointCloud2Ptr & |
point_cloud, |
|
|
std::size_t |
size |
|
) |
| |
|
protected |
sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::generatePointCloudFromDepth |
( |
sensor_msgs::ImageConstPtr |
depth_msg, |
|
|
sensor_msgs::ImageConstPtr |
color_msg, |
|
|
sensor_msgs::CameraInfoConstPtr |
camera_info_msg |
|
) |
| |
template<typename T >
sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::generatePointCloudML |
( |
const sensor_msgs::ImageConstPtr & |
depth_msg, |
|
|
std::vector< uint32_t > & |
rgba_color_raw |
|
) |
| |
|
protected |
template<typename T >
sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::generatePointCloudSL |
( |
const sensor_msgs::ImageConstPtr & |
depth_msg, |
|
|
std::vector< uint32_t > & |
rgba_color_raw |
|
) |
| |
|
protected |
void rviz::MultiLayerDepth::initializeConversion |
( |
const sensor_msgs::ImageConstPtr & |
depth_msg, |
|
|
sensor_msgs::CameraInfoConstPtr & |
camera_info_msg |
|
) |
| |
|
protected |
sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::initPointCloud |
( |
| ) |
|
|
protected |
void rviz::MultiLayerDepth::reset |
( |
| ) |
|
|
inline |
void rviz::MultiLayerDepth::setShadowTimeOut |
( |
double |
time_out | ) |
|
|
inline |
bool rviz::MultiLayerDepth::occlusion_compensation_ |
|
protected |
std::vector<float> rviz::MultiLayerDepth::projection_map_x_ |
|
protected |
std::vector<float> rviz::MultiLayerDepth::projection_map_y_ |
|
protected |
std::vector< uint8_t > rviz::MultiLayerDepth::shadow_buffer_ |
|
protected |
std::vector< float > rviz::MultiLayerDepth::shadow_depth_ |
|
protected |
float rviz::MultiLayerDepth::shadow_distance_ |
|
protected |
double rviz::MultiLayerDepth::shadow_time_out_ |
|
protected |
std::vector< double > rviz::MultiLayerDepth::shadow_timestamp_ |
|
protected |
The documentation for this class was generated from the following files: