depth_cloud_mld.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  *  Created on: Jan 22, 2013
00030  *      Author: jkammerl
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       // reset shadow buffer
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   // Helpers to generate pointcloud2 message
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   // shadow buffers
00127   std::vector< float > shadow_depth_;
00128   std::vector< double > shadow_timestamp_;
00129   std::vector< uint8_t > shadow_buffer_;
00130 
00131   // configuration
00132   bool occlusion_compensation_;
00133   double shadow_time_out_;
00134   float shadow_distance_;
00135 
00136 };
00137 
00138 }
00139 #endif /* MULTI_LAYER_DEPTH_H_ */


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Aug 27 2015 15:02:27