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
00034
00035
00036
00045 #ifndef PCL_ROS_CONVERSIONS_H_
00046 #define PCL_ROS_CONVERSIONS_H_
00047
00048 #include <sensor_msgs/PointField.h>
00049 #include <sensor_msgs/PointCloud2.h>
00050 #include <sensor_msgs/Image.h>
00051 #include <sensor_msgs/image_encodings.h>
00052 #include "pcl/point_cloud.h"
00053 #include "pcl/ros/point_traits.h"
00054 #include "pcl/ros/for_each_type.h"
00055 #include "pcl/exceptions.h"
00056 #include <boost/foreach.hpp>
00057
00058 namespace pcl
00059 {
00060 namespace detail
00061 {
00062
00063 template<typename PointT>
00064 struct FieldAdder
00065 {
00066 FieldAdder (std::vector<sensor_msgs::PointField>& fields) : fields_ (fields) {};
00067
00068 template<typename U> void operator() ()
00069 {
00070 sensor_msgs::PointField f;
00071 f.name = traits::name<PointT, U>::value;
00072 f.offset = traits::offset<PointT, U>::value;
00073 f.datatype = traits::datatype<PointT, U>::value;
00074 f.count = traits::datatype<PointT, U>::size;
00075 fields_.push_back (f);
00076 }
00077
00078 std::vector<sensor_msgs::PointField>& fields_;
00079 };
00080
00081
00082 template<typename PointT>
00083 struct FieldMapper
00084 {
00085 FieldMapper (const std::vector<sensor_msgs::PointField>& fields,
00086 std::vector<FieldMapping>& map)
00087 : fields_ (fields), map_ (map)
00088 {
00089 }
00090
00091 template<typename Tag> void operator() ()
00092 {
00093 const char* name = traits::name<PointT, Tag>::value;
00094 BOOST_FOREACH(const sensor_msgs::PointField& field, fields_)
00095 {
00096 if (field.name == name)
00097 {
00098 typedef traits::datatype<PointT, Tag> Data;
00099 assert (Data::value == field.datatype);
00100
00101
00102
00103 FieldMapping mapping;
00104 mapping.serialized_offset = field.offset;
00105 mapping.struct_offset = traits::offset<PointT, Tag>::value;
00106 mapping.size = sizeof (typename Data::type);
00107 map_.push_back (mapping);
00108 return;
00109 }
00110 }
00111
00112 std::stringstream ss;
00113 ss << "Failed to find a field named: '" << name
00114 << "'. Cannot convert message to PCL type.";
00115 ROS_ERROR ("%s", ss.str().c_str());
00116 throw pcl::InvalidConversionException(ss.str());
00117 }
00118
00119 const std::vector<sensor_msgs::PointField>& fields_;
00120 std::vector<FieldMapping>& map_;
00121 };
00122
00123 inline bool fieldOrdering(const FieldMapping& a, const FieldMapping& b)
00124 {
00125 return a.serialized_offset < b.serialized_offset;
00126 }
00127
00128 }
00129
00130 template<typename PointT>
00131 void createMapping (const std::vector<sensor_msgs::PointField>& msg_fields, MsgFieldMap& field_map)
00132 {
00133
00134 detail::FieldMapper<PointT> mapper (msg_fields, field_map);
00135 for_each_type< typename traits::fieldList<PointT>::type > (mapper);
00136
00137
00138 if (field_map.size() > 1)
00139 {
00140 std::sort(field_map.begin(), field_map.end(), detail::fieldOrdering);
00141 MsgFieldMap::iterator i = field_map.begin(), j = i + 1;
00142 while (j != field_map.end())
00143 {
00144
00147 if (j->serialized_offset - i->serialized_offset == j->struct_offset - i->struct_offset)
00148 {
00149 i->size += (j->struct_offset + j->size) - (i->struct_offset + i->size);
00150 j = field_map.erase(j);
00151 }
00152 else
00153 {
00154 ++i;
00155 ++j;
00156 }
00157 }
00158 }
00159 }
00160
00161 template<typename PointT>
00162 void fromROSMsg (const sensor_msgs::PointCloud2& msg, pcl::PointCloud<PointT>& cloud,
00163 const MsgFieldMap& field_map)
00164 {
00165
00166 cloud.header = msg.header;
00167 cloud.width = msg.width;
00168 cloud.height = msg.height;
00169 cloud.is_dense = msg.is_dense;
00170
00171
00172 uint32_t num_points = msg.width * msg.height;
00173 cloud.points.resize (num_points);
00174 uint8_t* cloud_data = reinterpret_cast<uint8_t*>(&cloud.points[0]);
00175
00176
00177 if (field_map.size() == 1 &&
00178 field_map[0].serialized_offset == 0 &&
00179 field_map[0].struct_offset == 0 &&
00180 msg.point_step == sizeof(PointT))
00181 {
00182 uint32_t cloud_row_step = sizeof(PointT) * cloud.width;
00183 const uint8_t* msg_data = &msg.data[0];
00184
00185 if (msg.row_step == cloud_row_step)
00186 {
00187 memcpy (cloud_data, msg_data, msg.data.size());
00188 }
00189 else
00190 {
00191 for (uint32_t i = 0; i < msg.height;
00192 ++i, cloud_data += cloud_row_step, msg_data += msg.row_step)
00193 memcpy (cloud_data, msg_data, cloud_row_step);
00194 }
00195 }
00196 else
00197 {
00198
00199 for (uint32_t row = 0; row < msg.height; ++row)
00200 {
00201 const uint8_t* row_data = &msg.data[row * msg.row_step];
00202 for (uint32_t col = 0; col < msg.width; ++col)
00203 {
00204 const uint8_t* msg_data = row_data + col * msg.point_step;
00205 BOOST_FOREACH (const detail::FieldMapping& mapping, field_map)
00206 {
00207 memcpy (cloud_data + mapping.struct_offset, msg_data + mapping.serialized_offset, mapping.size);
00208 }
00209 cloud_data += sizeof (PointT);
00210 }
00211 }
00212 }
00213 }
00214
00215 template<typename PointT>
00216 void fromROSMsg (const sensor_msgs::PointCloud2& msg, pcl::PointCloud<PointT>& cloud)
00217 {
00218 MsgFieldMap field_map;
00219 createMapping<PointT> (msg.fields, field_map);
00220 fromROSMsg (msg, cloud, field_map);
00221 }
00222
00223 template<typename PointT>
00224 void toROSMsg (const pcl::PointCloud<PointT>& cloud, sensor_msgs::PointCloud2& msg)
00225 {
00226
00227 if (cloud.width == 0 && cloud.height == 0)
00228 {
00229 msg.width = cloud.points.size ();
00230 msg.height = 1;
00231 }
00232 else
00233 {
00234 assert (cloud.points.size () == cloud.width * cloud.height);
00235 msg.height = cloud.height;
00236 msg.width = cloud.width;
00237 }
00238
00239
00240 size_t data_size = sizeof (PointT) * cloud.points.size ();
00241 msg.data.resize (data_size);
00242 memcpy (&msg.data[0], &cloud.points[0], data_size);
00243
00244
00245 msg.fields.clear ();
00246 for_each_type< typename traits::fieldList<PointT>::type > (detail::FieldAdder<PointT>(msg.fields));
00247
00248 msg.header = cloud.header;
00249 msg.point_step = sizeof (PointT);
00250 msg.row_step = sizeof (PointT) * msg.width;
00251 msg.is_dense = cloud.is_dense;
00253 }
00254
00261 template<typename CloudT> void
00262 toROSMsg(const CloudT& cloud, sensor_msgs::Image& msg)
00263 {
00264
00265 if (cloud.width == 0 && cloud.height == 0)
00266 throw std::runtime_error("Needs to be a dense like cloud!!");
00267 else
00268 {
00269 if(cloud.points.size () != cloud.width * cloud.height){
00270 throw std::runtime_error("The width and height do not match the cloud size!");
00271 }
00272 msg.height = cloud.height;
00273 msg.width = cloud.width;
00274 }
00275
00276 msg.encoding = sensor_msgs::image_encodings::BGR8;
00277 msg.step = msg.width * sizeof(uint8_t) * 3;
00278 msg.data.resize(msg.step * msg.height);
00279 for (size_t y = 0; y < cloud.height; y++)
00280 {
00281 for (size_t x = 0; x < cloud.width; x++)
00282 {
00283 uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
00284 memcpy(pixel, &cloud.at(x, y).rgb, 3 * sizeof(uint8_t));
00285 }
00286 }
00287 }
00293 inline void
00294 toROSMsg (const sensor_msgs::PointCloud2& cloud, sensor_msgs::Image& msg)
00295 {
00296 int rgb_index = -1;
00297
00298 for (size_t d = 0; d < cloud.fields.size (); ++d)
00299 if (cloud.fields[d].name == "rgb")
00300 {
00301 rgb_index = d;
00302 break;
00303 }
00304 if(rgb_index == -1){
00305 throw std::runtime_error ("No rgb field!!");
00306 }
00307 if (cloud.width == 0 && cloud.height == 0)
00308 throw std::runtime_error ("Needs to be a dense like cloud!!");
00309 else
00310 {
00311 msg.height = cloud.height;
00312 msg.width = cloud.width;
00313 }
00314 int rgb_offset = cloud.fields[rgb_index].offset;
00315 int point_step = cloud.point_step;
00316
00317 msg.encoding = sensor_msgs::image_encodings::BGR8;
00318 msg.step = msg.width * sizeof(uint8_t) * 3;
00319 msg.data.resize (msg.step * msg.height);
00320
00321 for (size_t y = 0; y < cloud.height; y++)
00322 {
00323 for (size_t x = 0; x < cloud.width; x++, rgb_offset += point_step)
00324 {
00325 uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
00326 memcpy (pixel, &(cloud.data[rgb_offset]), 3 * sizeof(uint8_t));
00327 }
00328 }
00329 }
00330 }
00331
00332 #endif //#ifndef PCL_ROS_CONVERSIONS_H_