38 #ifndef SENSOR_MSGS_POINT_CLOUD_CONVERSION_H 39 #define SENSOR_MSGS_POINT_CLOUD_CONVERSION_H 59 for (
size_t d = 0;
d < cloud.
fields.size (); ++
d)
60 if (cloud.
fields[
d].name == field_name)
80 for (
size_t d = 0;
d < output.
fields.size (); ++
d, offset += 4)
101 for (
size_t d = 0;
d < input.
channels.size (); ++
d)
127 if (x_idx == -1 || y_idx == -1 || z_idx == -1)
129 std::cerr <<
"x/y/z coordinates not found! Cannot convert to sensor_msgs::PointCloud!" << std::endl;
132 int x_offset = input.
fields[x_idx].offset;
133 int y_offset = input.
fields[y_idx].offset;
134 int z_offset = input.
fields[z_idx].offset;
141 for (
size_t d = 0;
d < input.
fields.size (); ++
d)
143 if ((
int)input.
fields[
d].offset == x_offset || (int)input.
fields[
d].offset == y_offset || (
int)input.
fields[
d].offset == z_offset)
154 output.
points[
cp].x = sensor_msgs::readPointCloud2BufferValue<float>(&input.
data[
cp * input.
point_step + x_offset], x_datatype);
155 output.
points[
cp].y = sensor_msgs::readPointCloud2BufferValue<float>(&input.
data[
cp * input.
point_step + y_offset], y_datatype);
156 output.
points[
cp].z = sensor_msgs::readPointCloud2BufferValue<float>(&input.
data[
cp * input.
point_step + z_offset], z_datatype);
159 for (
size_t d = 0;
d < input.
fields.size (); ++
d)
161 if ((
int)input.
fields[
d].offset == x_offset || (int)input.
fields[
d].offset == y_offset || (
int)input.
fields[
d].offset == z_offset)
169 #endif// SENSOR_MSGS_POINT_CLOUD_CONVERSION_H
static int getPointCloud2FieldIndex(const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
Get the index of a specified field (i.e., dimension/channel)
_is_bigendian_type is_bigendian
GLsizei const GLchar *const * string
static bool convertPointCloud2ToPointCloud(const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output)
Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message.
_point_step_type point_step
Tools for manipulating sensor_msgs.
static bool convertPointCloudToPointCloud2(const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message.
GLenum GLenum GLenum input