30 #include <OgreSceneNode.h>
31 #include <OgreSceneManager.h>
71 sensor_msgs::PointCloud2Ptr filtered(
new sensor_msgs::PointCloud2);
76 if (xi == -1 || yi == -1 || zi == -1)
81 const uint32_t xoff = cloud->fields[xi].offset;
82 const uint32_t yoff = cloud->fields[yi].offset;
83 const uint32_t zoff = cloud->fields[zi].offset;
84 const uint32_t point_step = cloud->point_step;
85 const size_t point_count = cloud->width * cloud->height;
87 if (point_count * point_step != cloud->data.size())
90 ss <<
"Data size (" << cloud->data.size() <<
" bytes) does not match width (" << cloud->width
91 <<
") times height (" << cloud->height <<
") times point_step (" << point_step
92 <<
"). Dropping message.";
97 filtered->data.resize(cloud->data.size());
98 uint32_t output_count;
105 uint8_t* output_ptr = &filtered->data.front();
106 const uint8_t *ptr = &cloud->data.front(), *ptr_end = &cloud->data.back(), *ptr_init;
107 size_t points_to_copy = 0;
108 for (; ptr < ptr_end; ptr += point_step)
110 float x = *
reinterpret_cast<const float*
>(ptr + xoff);
111 float y = *
reinterpret_cast<const float*
>(ptr + yoff);
112 float z = *
reinterpret_cast<const float*
>(ptr + zoff);
115 if (points_to_copy == 0)
131 memcpy(output_ptr, ptr_init, point_step * points_to_copy);
132 output_ptr += point_step * points_to_copy;
140 memcpy(output_ptr, ptr_init, point_step * points_to_copy);
141 output_ptr += point_step * points_to_copy;
143 output_count = (output_ptr - &filtered->data.front()) / point_step;
146 filtered->header = cloud->header;
147 filtered->fields = cloud->fields;
148 filtered->data.resize(output_count * point_step);
149 filtered->height = 1;
150 filtered->width = output_count;
151 filtered->is_bigendian = cloud->is_bigendian;
152 filtered->point_step = point_step;
153 filtered->row_step = output_count;