point_cloud2.cpp
Go to the documentation of this file.
1 #include <sensor_msgs/PointField.h>
2 #include <sensor_msgs/PointCloud2.h>
3 #include <ros/console.h>
4 
6 
7 #include <mrpt/version.h>
8 #include <mrpt/maps/CSimplePointsMap.h>
9 #include <mrpt/maps/CColouredPointsMap.h>
10 using namespace mrpt::maps;
11 
12 namespace mrpt_bridge
13 {
14 inline bool check_field(
15  const sensor_msgs::PointField& input_field, std::string check_name,
16  const sensor_msgs::PointField** output)
17 {
18  bool coherence_error = false;
19  if (input_field.name == check_name)
20  {
21  if (input_field.datatype != sensor_msgs::PointField::FLOAT32 &&
22  input_field.datatype != sensor_msgs::PointField::FLOAT64)
23  {
24  *output = NULL;
25  coherence_error = true;
26  }
27  else
28  {
29  *output = &input_field;
30  }
31  }
32  return coherence_error;
33 }
34 
36  const sensor_msgs::PointField* field, const unsigned char* data,
37  float& output)
38 {
39  if (field != NULL)
40  {
41  if (field->datatype == sensor_msgs::PointField::FLOAT32)
42  output = *(reinterpret_cast<const float*>(&data[field->offset]));
43  else
44  output =
45  (float)(*(reinterpret_cast<const double*>(&data[field->offset])));
46  }
47  else
48  output = 0.0;
49 }
50 
55 bool copy(const sensor_msgs::PointCloud2& msg, CSimplePointsMap& obj)
56 {
57  // Copy point data
58  unsigned int num_points = msg.width * msg.height;
59  obj.clear();
60  obj.reserve(num_points);
61 
62  bool incompatible_clouds = false;
63  const sensor_msgs::PointField *x_field = NULL, *y_field = NULL,
64  *z_field = NULL;
65 
66  for (unsigned int i = 0; i < msg.fields.size() && !incompatible_clouds; i++)
67  {
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);
71  }
72 
73  if (incompatible_clouds ||
74  (x_field == NULL && y_field == NULL && z_field == NULL))
75  return false;
76 
77  // If not, memcpy each group of contiguous fields separately
78  for (unsigned int row = 0; row < msg.height; ++row)
79  {
80  const unsigned char* row_data = &msg.data[row * msg.row_step];
81  for (uint32_t col = 0; col < msg.width; ++col)
82  {
83  const unsigned char* msg_data = row_data + col * msg.point_step;
84 
85  float x, y, z;
86  get_float_from_field(x_field, msg_data, x);
87  get_float_from_field(y_field, msg_data, y);
88  get_float_from_field(z_field, msg_data, z);
89  obj.insertPoint(x, y, z);
90  }
91  }
92 
93  return true;
94 }
95 
104 bool copy(
105  const CSimplePointsMap& obj, const std_msgs::Header& msg_header,
107 {
108  MRPT_TODO("Implement pointcloud2 mrpt2ros");
109  throw ros::Exception("not implemented yet.");
110  return true;
111 }
112 
113 } // namespace image_proc
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
Definition: map.h:30
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)


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Sat Apr 28 2018 02:49:17