Convert between the old (sensor_msgs::PointCloud) and the new (sensor_msgs::PointCloud2) format. More...
Namespaces | |
| namespace | distortion_models |
| namespace | image_encodings |
| namespace | point_cloud2 |
Functions | |
| static void | clearImage (Image &image) |
| static bool | convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output) |
| Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message. | |
| static bool | convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output) |
| Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message. | |
| static bool | fillImage (Image &image, const std::string &encoding_arg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, const void *data_arg) |
| static int | getPointCloud2FieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name) |
| Get the index of a specified field (i.e., dimension/channel) | |
Convert between the old (sensor_msgs::PointCloud) and the new (sensor_msgs::PointCloud2) format.
| static void sensor_msgs::clearImage | ( | Image & | image | ) | [inline, static] |
Definition at line 63 of file fill_image.h.
| static bool sensor_msgs::convertPointCloud2ToPointCloud | ( | const sensor_msgs::PointCloud2 & | input, |
| sensor_msgs::PointCloud & | output | ||
| ) | [inline, static] |
Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message.
| input | the message in the sensor_msgs::PointCloud2 format |
| output | the resultant message in the sensor_msgs::PointCloud format |
Definition at line 116 of file point_cloud_conversion.h.
| static bool sensor_msgs::convertPointCloudToPointCloud2 | ( | const sensor_msgs::PointCloud & | input, |
| sensor_msgs::PointCloud2 & | output | ||
| ) | [inline, static] |
Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message.
| input | the message in the sensor_msgs::PointCloud format |
| output | the resultant message in the sensor_msgs::PointCloud2 format |
Definition at line 69 of file point_cloud_conversion.h.
| static bool sensor_msgs::fillImage | ( | Image & | image, |
| const std::string & | encoding_arg, | ||
| uint32_t | rows_arg, | ||
| uint32_t | cols_arg, | ||
| uint32_t | step_arg, | ||
| const void * | data_arg | ||
| ) | [inline, static] |
Definition at line 44 of file fill_image.h.
| static int sensor_msgs::getPointCloud2FieldIndex | ( | const sensor_msgs::PointCloud2 & | cloud, |
| const std::string & | field_name | ||
| ) | [inline, static] |
Get the index of a specified field (i.e., dimension/channel)
| points | the the point cloud message |
| field_name | the string defining the field name |
Definition at line 55 of file point_cloud_conversion.h.