10 #include <sensor_msgs/PointField.h> 
   11 #include <sensor_msgs/PointCloud2.h> 
   16 #include <mrpt/version.h> 
   17 #include <mrpt/maps/CSimplePointsMap.h> 
   18 #include <mrpt/maps/CColouredPointsMap.h> 
   24         const sensor_msgs::PointField& input_field, std::string check_name,
 
   25         const sensor_msgs::PointField** output)
 
   27         bool coherence_error = 
false;
 
   28         if (input_field.name == check_name)
 
   30                 if (input_field.datatype != sensor_msgs::PointField::FLOAT32 &&
 
   31                         input_field.datatype != sensor_msgs::PointField::FLOAT64)
 
   34                         coherence_error = 
true;
 
   38                         *output = &input_field;
 
   41         return coherence_error;
 
   45         const sensor_msgs::PointField* field, 
const unsigned char* data,
 
   50                 if (field->datatype == sensor_msgs::PointField::FLOAT32)
 
   51                         output = *(
reinterpret_cast<const float*
>(&data[field->offset]));
 
   54                                 reinterpret_cast<const double*
>(&data[field->offset])));
 
   67         unsigned int num_points = msg.width * msg.height;
 
   69         obj.reserve(num_points);
 
   71         bool incompatible_clouds = 
false;
 
   72         const sensor_msgs::PointField *x_field = NULL, *y_field = NULL,
 
   75         for (
unsigned int i = 0; i < msg.fields.size() && !incompatible_clouds; i++)
 
   77                 incompatible_clouds |= 
check_field(msg.fields[i], 
"x", &x_field);
 
   78                 incompatible_clouds |= 
check_field(msg.fields[i], 
"y", &y_field);
 
   79                 incompatible_clouds |= 
check_field(msg.fields[i], 
"z", &z_field);
 
   82         if (incompatible_clouds ||
 
   83                 (x_field == NULL && y_field == NULL && z_field == NULL))
 
   87         for (
unsigned int row = 0; row < msg.height; ++row)
 
   89                 const unsigned char* row_data = &msg.data[row * msg.row_step];
 
   90                 for (uint32_t col = 0; col < msg.width; ++col)
 
   92                         const unsigned char* msg_data = row_data + col * msg.point_step;
 
   98                         obj.insertPoint(x, y, z);
 
  117         MRPT_TODO(
"Implement pointcloud2 mrpt2ros");