point_cloud.h
Go to the documentation of this file.
00001 #ifndef pcl_ROS_POINT_CLOUD_H_
00002 #define pcl_ROS_POINT_CLOUD_H_
00003 
00004 #include <ros/ros.h>
00005 #include <pcl/point_cloud.h>
00006 #include <pcl/point_traits.h>
00007 #include <pcl/for_each_type.h>
00008 #include <pcl/conversions.h>
00009 #include <pcl_conversions/pcl_conversions.h>
00010 #include <sensor_msgs/PointCloud2.h>
00011 #include <boost/mpl/size.hpp>
00012 #include <boost/ref.hpp>
00013 
00014 namespace pcl 
00015 {
00016   namespace detail 
00017   {
00018     template<typename Stream, typename PointT>
00019     struct FieldStreamer
00020     {
00021       FieldStreamer(Stream& stream) : stream_(stream) {}
00022 
00023       template<typename U> void operator() ()
00024       {
00025         const char* name = traits::name<PointT, U>::value;
00026         uint32_t name_length = strlen(name);
00027         stream_.next(name_length);
00028         if (name_length > 0)
00029           memcpy(stream_.advance(name_length), name, name_length);
00030 
00031         uint32_t offset = traits::offset<PointT, U>::value;
00032         stream_.next(offset);
00033 
00034         uint8_t datatype = traits::datatype<PointT, U>::value;
00035         stream_.next(datatype);
00036 
00037         uint32_t count = traits::datatype<PointT, U>::size;
00038         stream_.next(count);
00039       }
00040 
00041       Stream& stream_;
00042     };
00043 
00044     template<typename PointT>
00045     struct FieldsLength
00046     {
00047       FieldsLength() : length(0) {}
00048 
00049       template<typename U> void operator() ()
00050       {
00051         uint32_t name_length = strlen(traits::name<PointT, U>::value);
00052         length += name_length + 13;
00053       }
00054 
00055       uint32_t length;
00056     };
00057   } // namespace pcl::detail
00058 } // namespace pcl
00059 
00060 namespace ros 
00061 {
00062   // In ROS 1.3.1+, we can specialize the functor used to create PointCloud<T> objects
00063   // on the subscriber side. This allows us to generate the mapping between message
00064   // data and object fields only once and reuse it.
00065 #if ROS_VERSION_MINIMUM(1, 3, 1)
00066   template<typename T>
00067   struct DefaultMessageCreator<pcl::PointCloud<T> >
00068   {
00069     boost::shared_ptr<pcl::MsgFieldMap> mapping_;
00070 
00071     DefaultMessageCreator()
00072       : mapping_( boost::make_shared<pcl::MsgFieldMap>() )
00073     {
00074     }
00075     
00076     boost::shared_ptr<pcl::PointCloud<T> > operator() ()
00077     {
00078       boost::shared_ptr<pcl::PointCloud<T> > msg (new pcl::PointCloud<T> ());
00079       pcl::detail::getMapping(*msg) = mapping_;
00080       return msg;
00081     }
00082   };
00083 #endif
00084 
00085   namespace message_traits 
00086   {
00087     template<typename T> struct MD5Sum<pcl::PointCloud<T> >
00088     {
00089       static const char* value() { return MD5Sum<sensor_msgs::PointCloud2>::value(); }
00090       static const char* value(const pcl::PointCloud<T>&) { return value(); }
00091 
00092       static const uint64_t static_value1 = MD5Sum<sensor_msgs::PointCloud2>::static_value1;
00093       static const uint64_t static_value2 = MD5Sum<sensor_msgs::PointCloud2>::static_value2;
00094       
00095       // If the definition of sensor_msgs/PointCloud2 changes, we'll get a compile error here.
00096       ROS_STATIC_ASSERT(static_value1 == 0x1158d486dd51d683ULL);
00097       ROS_STATIC_ASSERT(static_value2 == 0xce2f1be655c3c181ULL);
00098     };
00099 
00100     template<typename T> struct DataType<pcl::PointCloud<T> >
00101     {
00102       static const char* value() { return DataType<sensor_msgs::PointCloud2>::value(); }
00103       static const char* value(const pcl::PointCloud<T>&) { return value(); }
00104     };
00105 
00106     template<typename T> struct Definition<pcl::PointCloud<T> >
00107     {
00108       static const char* value() { return Definition<sensor_msgs::PointCloud2>::value(); }
00109       static const char* value(const pcl::PointCloud<T>&) { return value(); }
00110     };
00111 
00112     // pcl point clouds message don't have a ROS compatible header
00113     // the specialized meta functions below (TimeStamp and FrameId)
00114     // can be used to get the header data.
00115     template<typename T> struct HasHeader<pcl::PointCloud<T> > : FalseType {};
00116 
00117     template<typename T>
00118     struct TimeStamp<pcl::PointCloud<T> >
00119     {
00120       // This specialization could be dangerous, but it's the best I can do.
00121       // If this TimeStamp struct is destroyed before they are done with the
00122       // pointer returned by the first functions may go out of scope, but there
00123       // isn't a lot I can do about that. This is a good reason to refuse to
00124       // returning pointers like this...
00125       static ros::Time* pointer(typename pcl::PointCloud<T> &m) {
00126         header_.reset(new std_msgs::Header());
00127         pcl_conversions::fromPCL(m.header, *(header_));
00128         return &(header_->stamp);
00129       }
00130       static ros::Time const* pointer(const typename pcl::PointCloud<T>& m) {
00131         header_const_.reset(new std_msgs::Header());
00132         pcl_conversions::fromPCL(m.header, *(header_const_));
00133         return &(header_const_->stamp);
00134       }
00135       static ros::Time value(const typename pcl::PointCloud<T>& m) {
00136         return pcl_conversions::fromPCL(m.header).stamp;
00137       }
00138     private:
00139       static boost::shared_ptr<std_msgs::Header> header_;
00140       static boost::shared_ptr<std_msgs::Header> header_const_;
00141     };
00142 
00143     template<typename T>
00144     struct FrameId<pcl::PointCloud<T> >
00145     {
00146       static std::string* pointer(pcl::PointCloud<T>& m) { return &m.header.frame_id; }
00147       static std::string const* pointer(const pcl::PointCloud<T>& m) { return &m.header.frame_id; }
00148       static std::string value(const pcl::PointCloud<T>& m) { return m.header.frame_id; }
00149     };
00150 
00151   } // namespace ros::message_traits
00152 
00153   namespace serialization 
00154   {
00155     template<typename T>
00156     struct Serializer<pcl::PointCloud<T> >
00157     {
00158       template<typename Stream>
00159       inline static void write(Stream& stream, const pcl::PointCloud<T>& m)
00160       {
00161         stream.next(m.header);
00162         
00163         // Ease the user's burden on specifying width/height for unorganized datasets
00164         uint32_t height = m.height, width = m.width;
00165         if (height == 0 && width == 0) {
00166           width = m.points.size();
00167           height = 1;
00168         }
00169         stream.next(height);
00170         stream.next(width);
00171 
00172         // Stream out point field metadata
00173         typedef typename pcl::traits::fieldList<T>::type FieldList;
00174         uint32_t fields_size = boost::mpl::size<FieldList>::value;
00175         stream.next(fields_size);
00176         pcl::for_each_type<FieldList>(pcl::detail::FieldStreamer<Stream, T>(stream));
00177 
00178         // Assume little-endian...
00179         uint8_t is_bigendian = false;
00180         stream.next(is_bigendian);
00181 
00182         // Write out point data as binary blob
00183         uint32_t point_step = sizeof(T);
00184         stream.next(point_step);
00185         uint32_t row_step = point_step * width;
00186         stream.next(row_step);
00187         uint32_t data_size = row_step * height;
00188         stream.next(data_size);
00189         memcpy(stream.advance(data_size), &m.points[0], data_size);
00190 
00191         uint8_t is_dense = m.is_dense;
00192         stream.next(is_dense);
00193       }
00194 
00195       template<typename Stream>
00196       inline static void read(Stream& stream, pcl::PointCloud<T>& m)
00197       {
00198         std_msgs::Header header;
00199         stream.next(header);
00200         pcl_conversions::toPCL(header, m.header);
00201         stream.next(m.height);
00202         stream.next(m.width);
00203 
00205         std::vector<sensor_msgs::PointField> fields;
00206         stream.next(fields);
00207 
00208         // Construct field mapping if deserializing for the first time
00209         boost::shared_ptr<pcl::MsgFieldMap>& mapping_ptr = pcl::detail::getMapping(m);
00210         if (!mapping_ptr)
00211         {
00212           // This normally should get allocated by DefaultMessageCreator, but just in case
00213           mapping_ptr = boost::make_shared<pcl::MsgFieldMap>();
00214         }
00215         pcl::MsgFieldMap& mapping = *mapping_ptr;
00216         if (mapping.empty())
00217           pcl::createMapping<T> (fields, mapping);
00218 
00219         uint8_t is_bigendian;
00220         stream.next(is_bigendian); // ignoring...
00221         uint32_t point_step, row_step;
00222         stream.next(point_step);
00223         stream.next(row_step);
00224 
00225         // Copy point data
00226         uint32_t data_size;
00227         stream.next(data_size);
00228         assert(data_size == m.height * m.width * point_step);
00229         m.points.resize(m.height * m.width);
00230         uint8_t* m_data = reinterpret_cast<uint8_t*>(&m.points[0]);
00231         // If the data layouts match, can copy a whole row in one memcpy
00232         if (mapping.size() == 1 &&
00233             mapping[0].serialized_offset == 0 &&
00234             mapping[0].struct_offset == 0 &&
00235             point_step == sizeof(T))
00236         {
00237           uint32_t m_row_step = sizeof(T) * m.width;
00238           // And if the row steps match, can copy whole point cloud in one memcpy
00239           if (m_row_step == row_step)
00240           {
00241             memcpy (m_data, stream.advance(data_size), data_size);
00242           }
00243           else
00244           {
00245             for (uint32_t i = 0; i < m.height; ++i, m_data += m_row_step)
00246               memcpy (m_data, stream.advance(row_step), m_row_step);
00247           }
00248         }
00249         else
00250         {
00251           // If not, do a lot of memcpys to copy over the fields
00252           for (uint32_t row = 0; row < m.height; ++row) {
00253             const uint8_t* stream_data = stream.advance(row_step);
00254             for (uint32_t col = 0; col < m.width; ++col, stream_data += point_step) {
00255               BOOST_FOREACH(const pcl::detail::FieldMapping& fm, mapping) {
00256                 memcpy(m_data + fm.struct_offset, stream_data + fm.serialized_offset, fm.size);
00257               }
00258               m_data += sizeof(T);
00259             }
00260           }
00261         }
00262 
00263         uint8_t is_dense;
00264         stream.next(is_dense);
00265         m.is_dense = is_dense;
00266       }
00267 
00268       inline static uint32_t serializedLength(const pcl::PointCloud<T>& m)
00269       {
00270         uint32_t length = 0;
00271 
00272         length += serializationLength(m.header);
00273         length += 8; // height/width
00274 
00275         pcl::detail::FieldsLength<T> fl;
00276         typedef typename pcl::traits::fieldList<T>::type FieldList;
00277         pcl::for_each_type<FieldList>(boost::ref(fl));
00278         length += 4; // size of 'fields'
00279         length += fl.length;
00280 
00281         length += 1; // is_bigendian
00282         length += 4; // point_step
00283         length += 4; // row_step
00284         length += 4; // size of 'data'
00285         length += m.points.size() * sizeof(T); // data
00286         length += 1; // is_dense
00287 
00288         return length;
00289       }
00290     };
00291   } // namespace ros::serialization
00292 
00294 
00295 } // namespace ros
00296 
00297 #endif


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu May 5 2016 04:16:43