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 76 shadow_time_out_ = time_out;
81 occlusion_compensation_ = occlusion_compensation;
85 sensor_msgs::PointCloud2Ptr
86 generatePointCloudFromDepth(sensor_msgs::ImageConstPtr depth_msg,
87 sensor_msgs::ImageConstPtr color_msg,
88 sensor_msgs::CameraInfoConstPtr camera_info_msg);
91 if (occlusion_compensation_)
94 memset(&shadow_depth_[0], 0,
sizeof(
float) * shadow_depth_.size());
95 memset(&shadow_buffer_[0], 0,
sizeof(uint8_t) * shadow_buffer_.size());
96 memset(&shadow_timestamp_[0], 0,
sizeof(
double) * shadow_timestamp_.size());
102 void initializeConversion(
const sensor_msgs::ImageConstPtr& depth_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>
111 sensor_msgs::PointCloud2Ptr generatePointCloudSL(
const sensor_msgs::ImageConstPtr& depth_msg,
112 std::vector<uint32_t>& rgba_color_raw);
115 template <
typename T>
116 sensor_msgs::PointCloud2Ptr generatePointCloudML(
const sensor_msgs::ImageConstPtr& depth_msg,
117 std::vector<uint32_t>& rgba_color_raw);
120 sensor_msgs::PointCloud2Ptr initPointCloud();
121 void finalizingPointCloud(sensor_msgs::PointCloud2Ptr& point_cloud, std::size_t size);
const char * what() const override
void enableOcclusionCompensation(bool occlusion_compensation)
MultiLayerDepthException(const std::string &error_msg)
std::vector< uint8_t > shadow_buffer_
std::vector< double > shadow_timestamp_
std::vector< float > shadow_depth_
std::vector< float > projection_map_y_
bool occlusion_compensation_
std::vector< float > projection_map_x_
void setShadowTimeOut(double time_out)
~MultiLayerDepthException() override
virtual ~MultiLayerDepth()