Point Cloud Library (PCL)  1.4.0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
conversions.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: conversions.h 3746 2011-12-31 22:19:47Z rusu $
00035  *
00036  */
00037 
00038 #ifndef PCL_ROS_CONVERSIONS_H_ 
00039 #define PCL_ROS_CONVERSIONS_H_
00040 
00041 #include <sensor_msgs/PointField.h>
00042 #include <sensor_msgs/PointCloud2.h>
00043 #include <sensor_msgs/Image.h>
00044 #include <pcl/point_cloud.h>
00045 #include <pcl/point_traits.h>
00046 #include <pcl/for_each_type.h>
00047 #include <pcl/exceptions.h>
00048 #include <pcl/console/print.h>
00049 #include <boost/foreach.hpp>
00050 
00051 namespace pcl
00052 {
00053   namespace detail
00054   {
00055     // For converting template point cloud to message.
00056     template<typename PointT>
00057     struct FieldAdder
00058     {
00059       FieldAdder (std::vector<sensor_msgs::PointField>& fields) : fields_ (fields) {};
00060       
00061       template<typename U> void operator() ()
00062       {
00063         sensor_msgs::PointField f;
00064         f.name = traits::name<PointT, U>::value;
00065         f.offset = traits::offset<PointT, U>::value;
00066         f.datatype = traits::datatype<PointT, U>::value;
00067         f.count = traits::datatype<PointT, U>::size;
00068         fields_.push_back (f);
00069       }
00070 
00071       std::vector<sensor_msgs::PointField>& fields_;
00072     };
00073 
00074     // For converting message to template point cloud.
00075     template<typename PointT>
00076     struct FieldMapper
00077     {
00078       FieldMapper (const std::vector<sensor_msgs::PointField>& fields,
00079                    std::vector<FieldMapping>& map)
00080         : fields_ (fields), map_ (map)
00081       {
00082       }
00083       
00084       template<typename Tag> void operator() ()
00085       {
00086         const char* name = traits::name<PointT, Tag>::value;
00087         BOOST_FOREACH(const sensor_msgs::PointField& field, fields_)
00088         {
00089           if (field.name == name)
00090           {
00091             typedef traits::datatype<PointT, Tag> Data;
00092             assert (Data::value == field.datatype);
00093             //@todo: Talk to Patrick about this
00094             //assert (Data::size  == field.count);
00095             
00096             FieldMapping mapping;
00097             mapping.serialized_offset = field.offset;
00098             mapping.struct_offset = traits::offset<PointT, Tag>::value;
00099             mapping.size = sizeof (typename Data::type);
00100             map_.push_back (mapping);
00101             return;
00102           }
00103         }
00104         // didn't find it...
00105         std::stringstream ss;
00106         ss << "Failed to find a field named: '" << name
00107            << "'. Cannot convert message to PCL type.";
00108         PCL_ERROR ("%s\n", ss.str().c_str());
00109         throw pcl::InvalidConversionException(ss.str());
00110       }
00111 
00112       const std::vector<sensor_msgs::PointField>& fields_;
00113       std::vector<FieldMapping>& map_;
00114     };
00115 
00116     inline bool fieldOrdering(const FieldMapping& a, const FieldMapping& b)
00117     {
00118       return a.serialized_offset < b.serialized_offset;
00119     }
00120 
00121   } //namespace detail
00122 
00123   template<typename PointT>
00124   void createMapping (const std::vector<sensor_msgs::PointField>& msg_fields, MsgFieldMap& field_map)
00125   {
00126     // Create initial 1-1 mapping between serialized data segments and struct fields
00127     detail::FieldMapper<PointT> mapper (msg_fields, field_map);
00128     for_each_type< typename traits::fieldList<PointT>::type > (mapper);
00129 
00130     // Coalesce adjacent fields into single memcpy's where possible
00131     if (field_map.size() > 1)
00132     {
00133       std::sort(field_map.begin(), field_map.end(), detail::fieldOrdering);
00134       MsgFieldMap::iterator i = field_map.begin(), j = i + 1;
00135       while (j != field_map.end())
00136       {
00137         // This check is designed to permit padding between adjacent fields.
00140         if (j->serialized_offset - i->serialized_offset == j->struct_offset - i->struct_offset)
00141         {
00142           i->size += (j->struct_offset + j->size) - (i->struct_offset + i->size);
00143           j = field_map.erase(j);
00144         }
00145         else
00146         {
00147           ++i;
00148           ++j;
00149         }
00150       }
00151     }
00152   }
00153 
00154   template<typename PointT>  
00155   void fromROSMsg (const sensor_msgs::PointCloud2& msg, pcl::PointCloud<PointT>& cloud,
00156                    const MsgFieldMap& field_map)
00157   {
00158     // Copy info fields
00159     cloud.header   = msg.header;
00160     cloud.width    = msg.width;
00161     cloud.height   = msg.height;
00162     cloud.is_dense = msg.is_dense == 1;
00163 
00164     // Copy point data
00165     uint32_t num_points = msg.width * msg.height;
00166     cloud.points.resize (num_points);
00167     uint8_t* cloud_data = reinterpret_cast<uint8_t*>(&cloud.points[0]);
00168 
00169     // Check if we can copy adjacent points in a single memcpy
00170     if (field_map.size() == 1 &&
00171         field_map[0].serialized_offset == 0 &&
00172         field_map[0].struct_offset == 0 &&
00173         msg.point_step == sizeof(PointT))
00174     {
00175       uint32_t cloud_row_step = sizeof(PointT) * cloud.width;
00176       const uint8_t* msg_data = &msg.data[0];
00177       // Should usually be able to copy all rows at once
00178       if (msg.row_step == cloud_row_step)
00179       {
00180         memcpy (cloud_data, msg_data, msg.data.size());
00181       }
00182       else
00183       {
00184         for (uint32_t i = 0; i < msg.height;
00185              ++i, cloud_data += cloud_row_step, msg_data += msg.row_step)
00186           memcpy (cloud_data, msg_data, cloud_row_step);
00187       }
00188     }
00189     else
00190     {
00191       // If not, memcpy each group of contiguous fields separately
00192       for (uint32_t row = 0; row < msg.height; ++row)
00193       {
00194         const uint8_t* row_data = &msg.data[row * msg.row_step];
00195         for (uint32_t col = 0; col < msg.width; ++col)
00196         {
00197           const uint8_t* msg_data = row_data + col * msg.point_step;
00198           BOOST_FOREACH (const detail::FieldMapping& mapping, field_map)
00199           {
00200             memcpy (cloud_data + mapping.struct_offset, msg_data + mapping.serialized_offset, mapping.size);
00201           }
00202           cloud_data += sizeof (PointT);
00203         }
00204       }
00205     }
00206   }
00207 
00208   template<typename PointT>  
00209   void fromROSMsg (const sensor_msgs::PointCloud2& msg, pcl::PointCloud<PointT>& cloud)
00210   {
00211     MsgFieldMap field_map;
00212     createMapping<PointT> (msg.fields, field_map);
00213     fromROSMsg (msg, cloud, field_map);
00214   }
00215 
00216   template<typename PointT>
00217   void toROSMsg (const pcl::PointCloud<PointT>& cloud, sensor_msgs::PointCloud2& msg)
00218   {
00219     // Ease the user's burden on specifying width/height for unorganized datasets
00220     if (cloud.width == 0 && cloud.height == 0)
00221     {
00222       msg.width  = (uint32_t) cloud.points.size ();
00223       msg.height = 1;
00224     }
00225     else
00226     {
00227       assert (cloud.points.size () == cloud.width * cloud.height);
00228       msg.height = cloud.height;
00229       msg.width  = cloud.width;
00230     }
00231 
00232     // Fill point cloud binary data (padding and all)
00233     size_t data_size = sizeof (PointT) * cloud.points.size ();
00234     msg.data.resize (data_size);
00235     memcpy (&msg.data[0], &cloud.points[0], data_size);
00236 
00237     // Fill fields metadata
00238     msg.fields.clear ();
00239     for_each_type< typename traits::fieldList<PointT>::type > (detail::FieldAdder<PointT>(msg.fields));
00240 
00241     msg.header     = cloud.header;
00242     msg.point_step = sizeof (PointT);
00243     msg.row_step   = sizeof (PointT) * msg.width;
00244     msg.is_dense   = cloud.is_dense;
00246   }
00247 
00254   template<typename CloudT> void
00255   toROSMsg(const CloudT& cloud, sensor_msgs::Image& msg)
00256   {
00257     // Ease the user's burden on specifying width/height for unorganized datasets
00258     if (cloud.width == 0 && cloud.height == 0)
00259       throw std::runtime_error("Needs to be a dense like cloud!!");
00260     else
00261     {
00262       if(cloud.points.size () != cloud.width * cloud.height){
00263         throw std::runtime_error("The width and height do not match the cloud size!");
00264       }
00265       msg.height = cloud.height;
00266       msg.width = cloud.width;
00267     }
00268 
00269     // ensor_msgs::image_encodings::BGR8;
00270     msg.encoding = "bgr8";
00271     msg.step = msg.width * sizeof(uint8_t) * 3;
00272     msg.data.resize(msg.step * msg.height);
00273     for (size_t y = 0; y < cloud.height; y++)
00274     {
00275       for (size_t x = 0; x < cloud.width; x++)
00276       {
00277         uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
00278         memcpy(pixel, &cloud (x, y).rgb, 3 * sizeof(uint8_t));
00279       }
00280     }
00281   }
00282 
00288   inline void
00289   toROSMsg (const sensor_msgs::PointCloud2& cloud, sensor_msgs::Image& msg)
00290   {
00291     int rgb_index = -1;
00292     // Get the index we need
00293     for (size_t d = 0; d < cloud.fields.size (); ++d)
00294       if (cloud.fields[d].name == "rgb")
00295       {
00296         rgb_index = (int) d;
00297         break;
00298       }
00299 
00300     if(rgb_index == -1)
00301       throw std::runtime_error ("No rgb field!!");
00302     if (cloud.width == 0 && cloud.height == 0)
00303       throw std::runtime_error ("Needs to be a dense like cloud!!");
00304     else
00305     {
00306       msg.height = cloud.height;
00307       msg.width = cloud.width;
00308     }
00309     int rgb_offset = cloud.fields[rgb_index].offset;
00310     int point_step = cloud.point_step;
00311 
00312     // sensor_msgs::image_encodings::BGR8;
00313     msg.encoding = "bgr8";
00314     msg.step = msg.width * sizeof(uint8_t) * 3;
00315     msg.data.resize (msg.step * msg.height);
00316 
00317     for (size_t y = 0; y < cloud.height; y++)
00318     {
00319       for (size_t x = 0; x < cloud.width; x++, rgb_offset += point_step)
00320       {
00321         uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
00322         memcpy (pixel, &(cloud.data[rgb_offset]), 3 * sizeof (uint8_t));
00323       }
00324     }
00325   }
00326 }
00327 
00328 #endif  //#ifndef PCL_ROS_CONVERSIONS_H_
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines