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
00034
00035
00036
00037
00038
00039
00040 #ifndef PCL_CONVERSIONS_H_
00041 #define PCL_CONVERSIONS_H_
00042
00043 #ifdef __GNUC__
00044 #pragma GCC system_header
00045 #endif
00046
00047 #include <pcl/PCLPointField.h>
00048 #include <pcl/PCLPointCloud2.h>
00049 #include <pcl/PCLImage.h>
00050 #include <pcl/point_cloud.h>
00051 #include <pcl/point_traits.h>
00052 #include <pcl/for_each_type.h>
00053 #include <pcl/exceptions.h>
00054 #include <pcl/console/print.h>
00055 #include <boost/foreach.hpp>
00056
00057 namespace pcl
00058 {
00059 namespace detail
00060 {
00061
00062 template<typename PointT>
00063 struct FieldAdder
00064 {
00065 FieldAdder (std::vector<pcl::PCLPointField>& fields) : fields_ (fields) {};
00066
00067 template<typename U> void operator() ()
00068 {
00069 pcl::PCLPointField f;
00070 f.name = traits::name<PointT, U>::value;
00071 f.offset = traits::offset<PointT, U>::value;
00072 f.datatype = traits::datatype<PointT, U>::value;
00073 f.count = traits::datatype<PointT, U>::size;
00074 fields_.push_back (f);
00075 }
00076
00077 std::vector<pcl::PCLPointField>& fields_;
00078 };
00079
00080
00081 template<typename PointT>
00082 struct FieldMapper
00083 {
00084 FieldMapper (const std::vector<pcl::PCLPointField>& fields,
00085 std::vector<FieldMapping>& map)
00086 : fields_ (fields), map_ (map)
00087 {
00088 }
00089
00090 template<typename Tag> void
00091 operator () ()
00092 {
00093 BOOST_FOREACH (const pcl::PCLPointField& field, fields_)
00094 {
00095 if (FieldMatches<PointT, Tag>()(field))
00096 {
00097 FieldMapping mapping;
00098 mapping.serialized_offset = field.offset;
00099 mapping.struct_offset = traits::offset<PointT, Tag>::value;
00100 mapping.size = sizeof (typename traits::datatype<PointT, Tag>::type);
00101 map_.push_back (mapping);
00102 return;
00103 }
00104 }
00105
00106 PCL_WARN ("Failed to find match for field '%s'.\n", traits::name<PointT, Tag>::value);
00107
00108 }
00109
00110 const std::vector<pcl::PCLPointField>& fields_;
00111 std::vector<FieldMapping>& map_;
00112 };
00113
00114 inline bool
00115 fieldOrdering (const FieldMapping& a, const FieldMapping& b)
00116 {
00117 return (a.serialized_offset < b.serialized_offset);
00118 }
00119
00120 }
00121
00122 template<typename PointT> void
00123 createMapping (const std::vector<pcl::PCLPointField>& msg_fields, MsgFieldMap& field_map)
00124 {
00125
00126 detail::FieldMapper<PointT> mapper (msg_fields, field_map);
00127 for_each_type< typename traits::fieldList<PointT>::type > (mapper);
00128
00129
00130 if (field_map.size() > 1)
00131 {
00132 std::sort(field_map.begin(), field_map.end(), detail::fieldOrdering);
00133 MsgFieldMap::iterator i = field_map.begin(), j = i + 1;
00134 while (j != field_map.end())
00135 {
00136
00139 if (j->serialized_offset - i->serialized_offset == j->struct_offset - i->struct_offset)
00140 {
00141 i->size += (j->struct_offset + j->size) - (i->struct_offset + i->size);
00142 j = field_map.erase(j);
00143 }
00144 else
00145 {
00146 ++i;
00147 ++j;
00148 }
00149 }
00150 }
00151 }
00152
00166 template <typename PointT> void
00167 fromPCLPointCloud2 (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud,
00168 const MsgFieldMap& field_map)
00169 {
00170
00171 cloud.header = msg.header;
00172 cloud.width = msg.width;
00173 cloud.height = msg.height;
00174 cloud.is_dense = msg.is_dense == 1;
00175
00176
00177 uint32_t num_points = msg.width * msg.height;
00178 cloud.points.resize (num_points);
00179 uint8_t* cloud_data = reinterpret_cast<uint8_t*>(&cloud.points[0]);
00180
00181
00182 if (field_map.size() == 1 &&
00183 field_map[0].serialized_offset == 0 &&
00184 field_map[0].struct_offset == 0 &&
00185 msg.point_step == sizeof(PointT))
00186 {
00187 uint32_t cloud_row_step = static_cast<uint32_t> (sizeof (PointT) * cloud.width);
00188 const uint8_t* msg_data = &msg.data[0];
00189
00190 if (msg.row_step == cloud_row_step)
00191 {
00192 memcpy (cloud_data, msg_data, msg.data.size ());
00193 }
00194 else
00195 {
00196 for (uint32_t i = 0; i < msg.height; ++i, cloud_data += cloud_row_step, msg_data += msg.row_step)
00197 memcpy (cloud_data, msg_data, cloud_row_step);
00198 }
00199
00200 }
00201 else
00202 {
00203
00204 for (uint32_t row = 0; row < msg.height; ++row)
00205 {
00206 const uint8_t* row_data = &msg.data[row * msg.row_step];
00207 for (uint32_t col = 0; col < msg.width; ++col)
00208 {
00209 const uint8_t* msg_data = row_data + col * msg.point_step;
00210 BOOST_FOREACH (const detail::FieldMapping& mapping, field_map)
00211 {
00212 memcpy (cloud_data + mapping.struct_offset, msg_data + mapping.serialized_offset, mapping.size);
00213 }
00214 cloud_data += sizeof (PointT);
00215 }
00216 }
00217 }
00218 }
00219
00224 template<typename PointT> void
00225 fromPCLPointCloud2 (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud)
00226 {
00227 MsgFieldMap field_map;
00228 createMapping<PointT> (msg.fields, field_map);
00229 fromPCLPointCloud2 (msg, cloud, field_map);
00230 }
00231
00236 template<typename PointT> void
00237 toPCLPointCloud2 (const pcl::PointCloud<PointT>& cloud, pcl::PCLPointCloud2& msg)
00238 {
00239
00240 if (cloud.width == 0 && cloud.height == 0)
00241 {
00242 msg.width = static_cast<uint32_t>(cloud.points.size ());
00243 msg.height = 1;
00244 }
00245 else
00246 {
00247 assert (cloud.points.size () == cloud.width * cloud.height);
00248 msg.height = cloud.height;
00249 msg.width = cloud.width;
00250 }
00251
00252
00253 size_t data_size = sizeof (PointT) * cloud.points.size ();
00254 msg.data.resize (data_size);
00255 memcpy (&msg.data[0], &cloud.points[0], data_size);
00256
00257
00258 msg.fields.clear ();
00259 for_each_type<typename traits::fieldList<PointT>::type> (detail::FieldAdder<PointT>(msg.fields));
00260
00261 msg.header = cloud.header;
00262 msg.point_step = sizeof (PointT);
00263 msg.row_step = static_cast<uint32_t> (sizeof (PointT) * msg.width);
00264 msg.is_dense = cloud.is_dense;
00266 }
00267
00274 template<typename CloudT> void
00275 toPCLPointCloud2 (const CloudT& cloud, pcl::PCLImage& msg)
00276 {
00277
00278 if (cloud.width == 0 && cloud.height == 0)
00279 throw std::runtime_error("Needs to be a dense like cloud!!");
00280 else
00281 {
00282 if (cloud.points.size () != cloud.width * cloud.height)
00283 throw std::runtime_error("The width and height do not match the cloud size!");
00284 msg.height = cloud.height;
00285 msg.width = cloud.width;
00286 }
00287
00288
00289 msg.encoding = "bgr8";
00290 msg.step = msg.width * sizeof (uint8_t) * 3;
00291 msg.data.resize (msg.step * msg.height);
00292 for (size_t y = 0; y < cloud.height; y++)
00293 {
00294 for (size_t x = 0; x < cloud.width; x++)
00295 {
00296 uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
00297 memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(uint8_t));
00298 }
00299 }
00300 }
00301
00307 inline void
00308 toPCLPointCloud2 (const pcl::PCLPointCloud2& cloud, pcl::PCLImage& msg)
00309 {
00310 int rgb_index = -1;
00311
00312 for (size_t d = 0; d < cloud.fields.size (); ++d)
00313 if (cloud.fields[d].name == "rgb")
00314 {
00315 rgb_index = static_cast<int>(d);
00316 break;
00317 }
00318
00319 if(rgb_index == -1)
00320 throw std::runtime_error ("No rgb field!!");
00321 if (cloud.width == 0 && cloud.height == 0)
00322 throw std::runtime_error ("Needs to be a dense like cloud!!");
00323 else
00324 {
00325 msg.height = cloud.height;
00326 msg.width = cloud.width;
00327 }
00328 int rgb_offset = cloud.fields[rgb_index].offset;
00329 int point_step = cloud.point_step;
00330
00331
00332 msg.encoding = "bgr8";
00333 msg.step = static_cast<uint32_t>(msg.width * sizeof (uint8_t) * 3);
00334 msg.data.resize (msg.step * msg.height);
00335
00336 for (size_t y = 0; y < cloud.height; y++)
00337 {
00338 for (size_t x = 0; x < cloud.width; x++, rgb_offset += point_step)
00339 {
00340 uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
00341 memcpy (pixel, &(cloud.data[rgb_offset]), 3 * sizeof (uint8_t));
00342 }
00343 }
00344 }
00345 }
00346
00347 #endif //#ifndef PCL_CONVERSIONS_H_