Go to the documentation of this file.
   33 #ifndef RVIZ_MULTI_LAYER_DEPTH_H_ 
   34 #define RVIZ_MULTI_LAYER_DEPTH_H_ 
   36 #include <boost/shared_ptr.hpp> 
   37 #include <boost/thread/mutex.hpp> 
   39 #include <sensor_msgs/Image.h> 
   40 #include <sensor_msgs/PointCloud2.h> 
   57   const char* 
what() 
const throw()
 override 
   85   sensor_msgs::PointCloud2Ptr
 
   87                               const sensor_msgs::ImageConstPtr& color_msg,
 
   88                               sensor_msgs::CameraInfoConstPtr camera_info_msg);
 
  103                             sensor_msgs::CameraInfoConstPtr& camera_info_msg);
 
  106   template <
typename T>
 
  107   void convertColor(
const sensor_msgs::ImageConstPtr& color_msg, std::vector<uint32_t>& rgba_color_raw);
 
  110   template <
typename T>
 
  112                                                    std::vector<uint32_t>& rgba_color_raw);
 
  115   template <
typename T>
 
  117                                                    std::vector<uint32_t>& rgba_color_raw);
 
  
void convertColor(const sensor_msgs::ImageConstPtr &color_msg, std::vector< uint32_t > &rgba_color_raw)
Convert color data to RGBA format.
sensor_msgs::PointCloud2Ptr generatePointCloudFromDepth(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &color_msg, sensor_msgs::CameraInfoConstPtr camera_info_msg)
MultiLayerDepthException(const std::string &error_msg)
sensor_msgs::PointCloud2Ptr generatePointCloudSL(const sensor_msgs::ImageConstPtr &depth_msg, std::vector< uint32_t > &rgba_color_raw)
Generate single-layered depth cloud (depth only)
std::vector< float > shadow_depth_
const char * what() const override
void enableOcclusionCompensation(bool occlusion_compensation)
std::vector< uint8_t > shadow_buffer_
std::vector< double > shadow_timestamp_
std::vector< float > projection_map_x_
virtual ~MultiLayerDepth()
void initializeConversion(const sensor_msgs::ImageConstPtr &depth_msg, sensor_msgs::CameraInfoConstPtr &camera_info_msg)
Precompute projection matrix, initialize buffers.
std::vector< float > projection_map_y_
void setShadowTimeOut(double time_out)
sensor_msgs::PointCloud2Ptr initPointCloud()
bool occlusion_compensation_
void finalizingPointCloud(sensor_msgs::PointCloud2Ptr &point_cloud, std::size_t size)
sensor_msgs::PointCloud2Ptr generatePointCloudML(const sensor_msgs::ImageConstPtr &depth_msg, std::vector< uint32_t > &rgba_color_raw)
Generate multi-layered depth cloud (depth+shadow)
~MultiLayerDepthException() override
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall 
autogenerated on Sun May 4 2025 02:31:26