Go to the documentation of this file.
13 #include <sensor_msgs/PointCloud2.h>
14 #include <sensor_msgs/PointField.h>
17 #include "cloud/impl/cloud.hpp"
23 typedef ::sensor_msgs::PointCloud2
Cloud;
26 typedef ::sensor_msgs::PointCloud2Iterator<float>
CloudIter;
70 return static_cast<size_t>(cloud.height) *
static_cast<size_t>(cloud.width);
132 #define CREATE_FILTERED_CLOUD(IN, OUT, KEEP_ORGANIZED, FILTER) {\
133 const auto inputIsOrganized = (IN).height > 1; \
134 const auto outIsOrganized = (KEEP_ORGANIZED) && inputIsOrganized; \
136 (OUT).header = (IN).header; \
137 (OUT).fields = (IN).fields; \
138 (OUT).point_step = (IN).point_step; \
139 (OUT).height = outIsOrganized ? (IN).height : 1; \
140 (OUT).width = outIsOrganized ? (IN).width : 0; \
142 (OUT).data.resize(0); \
143 (OUT).data.reserve((IN).data.size()); \
145 ::cras::CloudConstIter x_it((IN), "x"); \
146 ::cras::CloudConstIter y_it((IN), "y"); \
147 ::cras::CloudConstIter z_it((IN), "z"); \
149 const auto numPoints = ::cras::numPoints(IN); \
151 if (!outIsOrganized) { \
152 for (size_t i = 0; i < numPoints; ++i, ++x_it, ++y_it, ++z_it) { \
154 size_t from = (i / (IN).width) * (IN).row_step + (i % (IN).width) * (IN).point_step; \
155 size_t to = from + (IN).point_step; \
156 (OUT).data.insert((OUT).data.end(), (IN).data.begin() + from, \
157 (IN).data.begin() + to); \
161 (OUT).is_dense = true; \
163 (OUT).data.insert((OUT).data.end(), (IN).data.begin(), (IN).data.end()); \
165 ::cras::CloudIter x_out_it((OUT), "x"); \
166 ::cras::CloudIter y_out_it((OUT), "y"); \
167 ::cras::CloudIter z_out_it((OUT), "z"); \
168 const auto invalidValue = std::numeric_limits<float>::quiet_NaN(); \
170 for (size_t i = 0; i < numPoints; ++i, ++x_it, ++y_it, ++z_it, ++x_out_it, ++y_out_it, ++z_out_it) { \
172 *x_out_it = *y_out_it = *z_out_it = invalidValue; \
173 (OUT).is_dense = false; \
178 (OUT).row_step = (OUT).width * (OUT).point_step;\
::sensor_msgs::PointCloud2ConstIterator< float > CloudConstIter
Const cloud float field iterator.
::sensor_msgs::PointCloud2ConstIterator< int > CloudIndexConstIter
Const cloud int field iterator.
::sensor_msgs::PointCloud2Iterator< int > CloudIndexIter
Cloud int field iterator.
bool hasField(const ::cras::Cloud &cloud, const ::std::string &fieldName)
Return true if the cloud contains a field with the given name.
size_t numPoints(const ::cras::Cloud &cloud)
Return the number of points the given pointcloud contains.
::cras::impl::GenericCloudConstIterator GenericCloudConstIter
::cras::impl::GenericCloudIterator GenericCloudIter
GenericCloudIter and GenericCloudConstIter are iterators of fields of types unknown at compile time.
void copyChannelData(const ::cras::Cloud &in, ::cras::Cloud &out, const ::std::string &fieldName)
Copy data belonging to the given field from in cloud to out cloud.
::sensor_msgs::PointCloud2Modifier CloudModifier
Shorthand for sensor_msgs::PointCloud2Modifier.
size_t sizeOfPointField(int datatype)
Return the size (in bytes) of a sensor_msgs::PointField datatype.
::sensor_msgs::PointField & getField(::cras::Cloud &cloud, const ::std::string &fieldName)
Return the sensor_msgs::PointField with the given name.
::sensor_msgs::PointCloud2 Cloud
Shorthand for sensor_msgs::PointCloud2.
::sensor_msgs::PointCloud2Iterator< float > CloudIter
Cloud float field iterator.
cras_cpp_common
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:03