#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 66 of file depth_cloud_mld.h.
 
◆ MultiLayerDepth()
  
  | 
        
          | rviz::MultiLayerDepth::MultiLayerDepth | ( |  | ) |  |  | inline | 
 
 
◆ ~MultiLayerDepth()
  
  | 
        
          | virtual rviz::MultiLayerDepth::~MultiLayerDepth | ( |  | ) |  |  | inlinevirtual | 
 
 
◆ convertColor()
template<typename T > 
  
  | 
        
          | void rviz::MultiLayerDepth::convertColor | ( | const sensor_msgs::ImageConstPtr & | color_msg, |  
          |  |  | std::vector< uint32_t > & | rgba_color_raw |  
          |  | ) |  |  |  | protected | 
 
 
◆ enableOcclusionCompensation()
  
  | 
        
          | void rviz::MultiLayerDepth::enableOcclusionCompensation | ( | bool | occlusion_compensation | ) |  |  | inline | 
 
 
◆ finalizingPointCloud()
  
  | 
        
          | void rviz::MultiLayerDepth::finalizingPointCloud | ( | sensor_msgs::PointCloud2Ptr & | point_cloud, |  
          |  |  | std::size_t | size |  
          |  | ) |  |  |  | protected | 
 
 
◆ generatePointCloudFromDepth()
      
        
          | sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::generatePointCloudFromDepth | ( | const sensor_msgs::ImageConstPtr & | depth_msg, | 
        
          |  |  | const sensor_msgs::ImageConstPtr & | color_msg, | 
        
          |  |  | sensor_msgs::CameraInfoConstPtr | camera_info_msg | 
        
          |  | ) |  |  | 
      
 
 
◆ generatePointCloudML()
template<typename T > 
  
  | 
        
          | sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::generatePointCloudML | ( | const sensor_msgs::ImageConstPtr & | depth_msg, |  
          |  |  | std::vector< uint32_t > & | rgba_color_raw |  
          |  | ) |  |  |  | protected | 
 
 
◆ generatePointCloudSL()
template<typename T > 
  
  | 
        
          | sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::generatePointCloudSL | ( | const sensor_msgs::ImageConstPtr & | depth_msg, |  
          |  |  | std::vector< uint32_t > & | rgba_color_raw |  
          |  | ) |  |  |  | protected | 
 
 
◆ initializeConversion()
  
  | 
        
          | void rviz::MultiLayerDepth::initializeConversion | ( | const sensor_msgs::ImageConstPtr & | depth_msg, |  
          |  |  | sensor_msgs::CameraInfoConstPtr & | camera_info_msg |  
          |  | ) |  |  |  | protected | 
 
 
◆ initPointCloud()
  
  | 
        
          | sensor_msgs::PointCloud2Ptr rviz::MultiLayerDepth::initPointCloud | ( |  | ) |  |  | protected | 
 
 
◆ reset()
  
  | 
        
          | void rviz::MultiLayerDepth::reset | ( |  | ) |  |  | inline | 
 
 
◆ setShadowTimeOut()
  
  | 
        
          | void rviz::MultiLayerDepth::setShadowTimeOut | ( | double | time_out | ) |  |  | inline | 
 
 
◆ occlusion_compensation_
  
  | 
        
          | bool rviz::MultiLayerDepth::occlusion_compensation_ |  | protected | 
 
 
◆ projection_map_x_
  
  | 
        
          | std::vector<float> rviz::MultiLayerDepth::projection_map_x_ |  | protected | 
 
 
◆ projection_map_y_
  
  | 
        
          | std::vector<float> rviz::MultiLayerDepth::projection_map_y_ |  | protected | 
 
 
◆ shadow_buffer_
  
  | 
        
          | std::vector<uint8_t> rviz::MultiLayerDepth::shadow_buffer_ |  | protected | 
 
 
◆ shadow_depth_
  
  | 
        
          | std::vector<float> rviz::MultiLayerDepth::shadow_depth_ |  | protected | 
 
 
◆ shadow_distance_
  
  | 
        
          | float rviz::MultiLayerDepth::shadow_distance_ |  | protected | 
 
 
◆ shadow_time_out_
  
  | 
        
          | double rviz::MultiLayerDepth::shadow_time_out_ |  | protected | 
 
 
◆ shadow_timestamp_
  
  | 
        
          | std::vector<double> rviz::MultiLayerDepth::shadow_timestamp_ |  | protected | 
 
 
The documentation for this class was generated from the following files:
 
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall 
autogenerated on Sun May 4 2025 02:31:27