Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #ifndef RVIZ_MULTI_LAYER_DEPTH_H_
00034 #define RVIZ_MULTI_LAYER_DEPTH_H_
00035
00036 #include <boost/shared_ptr.hpp>
00037 #include <boost/thread/mutex.hpp>
00038
00039 #include <sensor_msgs/Image.h>
00040 #include <sensor_msgs/PointCloud2.h>
00041
00042 #include <vector>
00043 #include <exception>
00044
00045 namespace rviz
00046 {
00047
00048 class MultiLayerDepthException: public std::exception
00049 {
00050 public:
00051 MultiLayerDepthException(const std::string& error_msg) :
00052 std::exception(), error_msg_(error_msg) {
00053 }
00054 virtual ~MultiLayerDepthException() throw () {}
00055
00056 virtual const char * what() const throw () {
00057 return error_msg_.c_str();
00058 }
00059
00060 protected:
00061 std::string error_msg_;
00062 };
00063
00064 class MultiLayerDepth
00065 {
00066 public:
00067 MultiLayerDepth() :
00068 shadow_time_out_(30.0),
00069 shadow_distance_(0.01)
00070 {};
00071 virtual ~MultiLayerDepth() {
00072 }
00073
00074 void setShadowTimeOut(double time_out)
00075 {
00076 shadow_time_out_ = time_out;
00077 }
00078
00079 void enableOcclusionCompensation(bool occlusion_compensation)
00080 {
00081 occlusion_compensation_ = occlusion_compensation;
00082 reset();
00083 }
00084
00085 sensor_msgs::PointCloud2Ptr generatePointCloudFromDepth (sensor_msgs::ImageConstPtr depth_msg,
00086 sensor_msgs::ImageConstPtr color_msg,
00087 sensor_msgs::CameraInfoConstPtr camera_info_msg);
00088 void reset()
00089 {
00090 if (occlusion_compensation_)
00091 {
00092
00093 memset(&shadow_depth_[0], 0, sizeof(float)*shadow_depth_.size());
00094 memset(&shadow_buffer_[0], 0, sizeof(uint8_t)*shadow_buffer_.size());
00095 memset(&shadow_timestamp_[0], 0, sizeof(double)*shadow_timestamp_.size());
00096 }
00097 }
00098
00099 protected:
00101 void initializeConversion(const sensor_msgs::ImageConstPtr& depth_msg,
00102 sensor_msgs::CameraInfoConstPtr& camera_info_msg);
00103
00105 template<typename T>
00106 void convertColor(const sensor_msgs::ImageConstPtr& color_msg,
00107 std::vector<uint32_t>& rgba_color_raw);
00108
00110 template<typename T>
00111 sensor_msgs::PointCloud2Ptr generatePointCloudSL(const sensor_msgs::ImageConstPtr& depth_msg,
00112 std::vector<uint32_t>& rgba_color_raw);
00113
00115 template<typename T>
00116 sensor_msgs::PointCloud2Ptr generatePointCloudML(const sensor_msgs::ImageConstPtr& depth_msg,
00117 std::vector<uint32_t>& rgba_color_raw);
00118
00119
00120 sensor_msgs::PointCloud2Ptr initPointCloud();
00121 void finalizingPointCloud(sensor_msgs::PointCloud2Ptr& point_cloud, std::size_t size);
00122
00123 std::vector<float> projection_map_x_;
00124 std::vector<float> projection_map_y_;
00125
00126
00127 std::vector< float > shadow_depth_;
00128 std::vector< double > shadow_timestamp_;
00129 std::vector< uint8_t > shadow_buffer_;
00130
00131
00132 bool occlusion_compensation_;
00133 double shadow_time_out_;
00134 float shadow_distance_;
00135
00136 };
00137
00138 }
00139 #endif