1 #ifndef pcl_ROS_POINT_CLOUD_H_ 
    2 #define pcl_ROS_POINT_CLOUD_H_ 
    5 #include <pcl/point_cloud.h> 
    6 #include <pcl/pcl_config.h>  
    7 #if PCL_VERSION_COMPARE(>=, 1, 11, 0) 
    8 #include <pcl/type_traits.h> 
   10 #include <pcl/point_traits.h> 
   11 #endif // PCL_VERSION_COMPARE(>=, 1, 11, 0) 
   12 #include <pcl/for_each_type.h> 
   13 #include <pcl/conversions.h> 
   15 #include <sensor_msgs/PointCloud2.h> 
   16 #include <boost/foreach.hpp>  
   17 #include <boost/mpl/size.hpp> 
   18 #include <boost/ref.hpp> 
   19 #include <boost/thread/mutex.hpp> 
   25     template<
typename Stream, 
typename Po
intT>
 
   32         const char* name = pcl::traits::name<PointT, U>::value;
 
   33         std::uint32_t name_length = strlen(name);
 
   36           memcpy(
stream_.advance(name_length), name, name_length);
 
   38         std::uint32_t offset = pcl::traits::offset<PointT, U>::value;
 
   41         std::uint8_t 
datatype = pcl::traits::datatype<PointT, U>::value;
 
   44         std::uint32_t count = pcl::traits::datatype<PointT, U>::size;
 
   51     template<
typename Po
intT>
 
   58         std::uint32_t name_length = strlen(pcl::traits::name<PointT, U>::value);
 
   59         length += name_length + 13;
 
   69   namespace message_traits 
 
   74       static const char* 
value(
const pcl::PointCloud<T>&) { 
return value(); }
 
   87       static const char* 
value(
const pcl::PointCloud<T>&) { 
return value(); }
 
   93       static const char* 
value(
const pcl::PointCloud<T>&) { 
return value(); }
 
  110         header_.reset(
new std_msgs::Header());
 
  112         return &(header_->stamp);
 
  115         header_const_.reset(
new std_msgs::Header());
 
  117         return &(header_const_->stamp);
 
  130       static std::string* 
pointer(pcl::PointCloud<T>& m) { 
return &m.header.frame_id; }
 
  131       static std::string 
const* 
pointer(
const pcl::PointCloud<T>& m) { 
return &m.header.frame_id; }
 
  132       static std::string 
value(
const pcl::PointCloud<T>& m) { 
return m.header.frame_id; }
 
  137   namespace serialization 
 
  142       template<
typename Stream>
 
  143       inline static void write(
Stream& stream, 
const pcl::PointCloud<T>& m)
 
  145         stream.next(m.header);
 
  148         uint32_t height = m.height, width = m.width;
 
  149         if (height == 0 && width == 0) {
 
  150           width = m.points.size();
 
  157         typedef typename pcl::traits::fieldList<T>::type FieldList;
 
  158         uint32_t fields_size = boost::mpl::size<FieldList>::value;
 
  159         stream.next(fields_size);
 
  163         uint8_t is_bigendian = 
false;
 
  164         stream.next(is_bigendian);
 
  167         uint32_t point_step = 
sizeof(T);
 
  168         stream.next(point_step);
 
  169         uint32_t row_step = point_step * width;
 
  170         stream.next(row_step);
 
  171         uint32_t data_size = row_step * height;
 
  172         stream.next(data_size);
 
  173         memcpy(stream.
advance(data_size), m.points.data(), data_size);
 
  175         uint8_t is_dense = m.is_dense;
 
  176         stream.next(is_dense);
 
  179       template<
typename Stream>
 
  180       inline static void read(
Stream& stream, pcl::PointCloud<T>& m)
 
  185         stream.next(m.height);
 
  186         stream.next(m.width);
 
  189         std::vector<sensor_msgs::PointField> fields;
 
  193         static pcl::MsgFieldMap mapping;
 
  194         static boost::mutex mutex;
 
  197           boost::mutex::scoped_lock lock(mutex);
 
  198           pcl::createMapping<T>(fields, mapping);
 
  201         uint8_t is_bigendian;
 
  202         stream.next(is_bigendian); 
 
  203         uint32_t point_step, row_step;
 
  204         stream.next(point_step);
 
  205         stream.next(row_step);
 
  209         stream.next(data_size);
 
  210         assert(data_size == m.height * m.width * point_step);
 
  211         m.points.resize(m.height * m.width);
 
  212         uint8_t* m_data = 
reinterpret_cast<uint8_t*
>(m.points.data());
 
  214         if (mapping.size() == 1 &&
 
  215             mapping[0].serialized_offset == 0 &&
 
  216             mapping[0].struct_offset == 0 &&
 
  217             point_step == 
sizeof(T))
 
  219           uint32_t m_row_step = 
sizeof(T) * m.width;
 
  221           if (m_row_step == row_step)
 
  223             memcpy (m_data, stream.
advance(data_size), data_size);
 
  227             for (uint32_t i = 0; i < m.height; ++i, m_data += m_row_step)
 
  228               memcpy (m_data, stream.
advance(row_step), m_row_step);
 
  234           for (uint32_t row = 0; row < m.height; ++row) {
 
  235             const uint8_t* stream_data = stream.
advance(row_step);
 
  236             for (uint32_t col = 0; col < m.width; ++col, stream_data += point_step) {
 
  237               BOOST_FOREACH(
const pcl::detail::FieldMapping& fm, mapping) {
 
  238                 memcpy(m_data + fm.struct_offset, stream_data + fm.serialized_offset, fm.size);
 
  246         stream.next(is_dense);
 
  247         m.is_dense = is_dense;
 
  258         typedef typename pcl::traits::fieldList<T>::type FieldList;
 
  259         pcl::for_each_type<FieldList>(boost::ref(fl));
 
  267         length += m.points.size() * 
sizeof(T); 
 
  280 #if defined(__cpp_rvalue_references) && defined(__cpp_constexpr) 
  281 #define ROS_POINTER_COMPATIBILITY_IMPLEMENTED 1 
  283 #define ROS_POINTER_COMPATIBILITY_IMPLEMENTED 0 
  286 #if ROS_POINTER_COMPATIBILITY_IMPLEMENTED 
  287 #include <type_traits>   
  290 #if PCL_VERSION_COMPARE(>=, 1, 11, 0) 
  291 #include <pcl/memory.h> 
  292 #elif PCL_VERSION_COMPARE(>=, 1, 10, 0) 
  293 #include <pcl/make_shared.h> 
  301 #if ROS_POINTER_COMPATIBILITY_IMPLEMENTED 
  302 #if PCL_VERSION_COMPARE(>=, 1, 10, 0) 
  304     constexpr 
static bool pcl_uses_boost = std::is_same<boost::shared_ptr<T>,
 
  305                                                         pcl::shared_ptr<T>>::value;
 
  308     constexpr 
static bool pcl_uses_boost = 
true;
 
  311     template<
class SharedPo
inter> 
struct Holder
 
  315       Holder(
const SharedPointer &p) : p(p) {}
 
  316       Holder(
const Holder &other) : p(other.p) {}
 
  317       Holder(Holder &&other) : p(std::move(other.p)) {}
 
  319       void operator () (...) { p.reset(); }
 
  325         typedef Holder<std::shared_ptr<T>> H;
 
  326         if(H *h = boost::get_deleter<H>(p))
 
  339         typedef Holder<boost::shared_ptr<T>> H;
 
  340         if(H * h = std::get_deleter<H>(p))
 
  359 #if ROS_POINTER_COMPATIBILITY_IMPLEMENTED 
  363       return detail::to_boost_ptr(p);
 
  367   template <
class T, 
class = 
typename std::enable_if<!detail::pcl_uses_boost<T>>::type>
 
  368   inline std::shared_ptr<T> 
pcl_ptr(
const std::shared_ptr<T> &p)
 
  373   template <
class T, 
class = 
typename std::enable_if<!detail::pcl_uses_boost<T>>::type>
 
  376       return detail::to_std_ptr(p);
 
  379   template <
class T, 
class = 
typename std::enable_if<detail::pcl_uses_boost<T>>::type>
 
  382       return detail::to_boost_ptr(p);
 
  385   template <
class T, 
class = 
typename std::enable_if<detail::pcl_uses_boost<T>>::type>