1 #include <sensor_msgs/PointField.h> 2 #include <sensor_msgs/PointCloud2.h> 7 #include <mrpt/version.h> 8 #include <mrpt/maps/CSimplePointsMap.h> 9 #include <mrpt/maps/CColouredPointsMap.h> 15 const sensor_msgs::PointField& input_field, std::string check_name,
16 const sensor_msgs::PointField** output)
18 bool coherence_error =
false;
19 if (input_field.name == check_name)
21 if (input_field.datatype != sensor_msgs::PointField::FLOAT32 &&
22 input_field.datatype != sensor_msgs::PointField::FLOAT64)
25 coherence_error =
true;
29 *output = &input_field;
32 return coherence_error;
36 const sensor_msgs::PointField* field,
const unsigned char* data,
41 if (field->datatype == sensor_msgs::PointField::FLOAT32)
42 output = *(
reinterpret_cast<const float*
>(&data[field->offset]));
45 (float)(*(reinterpret_cast<const double*>(&data[field->offset])));
58 unsigned int num_points = msg.width * msg.height;
60 obj.reserve(num_points);
62 bool incompatible_clouds =
false;
63 const sensor_msgs::PointField *x_field = NULL, *y_field = NULL,
66 for (
unsigned int i = 0; i < msg.fields.size() && !incompatible_clouds; i++)
68 incompatible_clouds |=
check_field(msg.fields[i],
"x", &x_field);
69 incompatible_clouds |=
check_field(msg.fields[i],
"y", &y_field);
70 incompatible_clouds |=
check_field(msg.fields[i],
"z", &z_field);
73 if (incompatible_clouds ||
74 (x_field == NULL && y_field == NULL && z_field == NULL))
78 for (
unsigned int row = 0; row < msg.height; ++row)
80 const unsigned char* row_data = &msg.data[row * msg.row_step];
81 for (uint32_t col = 0; col < msg.width; ++col)
83 const unsigned char* msg_data = row_data + col * msg.point_step;
89 obj.insertPoint(x, y, z);
108 MRPT_TODO(
"Implement pointcloud2 mrpt2ros");
bool copy(const CSimplePointsMap &obj, const std_msgs::Header &msg_header, sensor_msgs::PointCloud2 &msg)
void get_float_from_field(const sensor_msgs::PointField *field, const unsigned char *data, float &output)
TFSIMD_FORCE_INLINE const tfScalar & y() const
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
bool check_field(const sensor_msgs::PointField &input_field, std::string check_name, const sensor_msgs::PointField **output)