Namespaces | Classes | Functions
sensor_msgs Namespace Reference

Tools for manipulating sensor_msgs. More...

Namespaces

 distortion_models
 
 image_encodings
 
 impl
 
 point_cloud2
 

Classes

class  PointCloud2ConstIterator
 Same as a PointCloud2Iterator but for const data. More...
 
class  PointCloud2Iterator
 Class that can iterate over a PointCloud2. More...
 
class  PointCloud2Modifier
 Enables modifying a sensor_msgs::PointCloud2 like a container. More...
 
struct  pointFieldTypeAsType
 
struct  pointFieldTypeAsType< sensor_msgs::PointField::FLOAT32 >
 
struct  pointFieldTypeAsType< sensor_msgs::PointField::FLOAT64 >
 
struct  pointFieldTypeAsType< sensor_msgs::PointField::INT16 >
 
struct  pointFieldTypeAsType< sensor_msgs::PointField::INT32 >
 
struct  pointFieldTypeAsType< sensor_msgs::PointField::INT8 >
 
struct  pointFieldTypeAsType< sensor_msgs::PointField::UINT16 >
 
struct  pointFieldTypeAsType< sensor_msgs::PointField::UINT32 >
 
struct  pointFieldTypeAsType< sensor_msgs::PointField::UINT8 >
 
struct  typeAsPointFieldType
 
struct  typeAsPointFieldType< double >
 
struct  typeAsPointFieldType< float >
 
struct  typeAsPointFieldType< int16_t >
 
struct  typeAsPointFieldType< int32_t >
 
struct  typeAsPointFieldType< int8_t >
 
struct  typeAsPointFieldType< uint16_t >
 
struct  typeAsPointFieldType< uint32_t >
 
struct  typeAsPointFieldType< uint8_t >
 

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. More...
 
static bool convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
 Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message. More...
 
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) More...
 
template<int point_field_type, typename T >
readPointCloud2BufferValue (const unsigned char *data_ptr)
 
template<typename T >
readPointCloud2BufferValue (const unsigned char *data_ptr, const unsigned char datatype)
 
template<int point_field_type, typename T >
void writePointCloud2BufferValue (unsigned char *data_ptr, T value)
 
template<typename T >
void writePointCloud2BufferValue (unsigned char *data_ptr, const unsigned char datatype, T value)
 

Detailed Description

Tools for manipulating sensor_msgs.

This file provides a type to enum mapping for the different PointField types and methods to read and write in a PointCloud2 buffer for the different PointField types.

Convert between the old (sensor_msgs::PointCloud) and the new (sensor_msgs::PointCloud2) format.

This file provides two sets of utilities to modify and parse PointCloud2 The first set allows you to conveniently set the fields by hand:

  #include <sensor_msgs/point_cloud_iterator.h>
  // Create a PointCloud2
  sensor_msgs::PointCloud2 cloud_msg;
  // Fill some internals of the PoinCloud2 like the header/width/height ...
  cloud_msgs.height = 1;  cloud_msgs.width = 4;
  // Set the point fields to xyzrgb and resize the vector with the following command
  // 4 is for the number of added fields. Each come in triplet: the name of the PointField,
  // the number of occurrences of the type in the PointField, the type of the PointField
  sensor_msgs::PointCloud2Modifier modifier(cloud_msg);
  modifier.setPointCloud2Fields(4, "x", 1, sensor_msgs::PointField::FLOAT32,
                                           "y", 1, sensor_msgs::PointField::FLOAT32,
                                           "z", 1, sensor_msgs::PointField::FLOAT32,
                                           "rgb", 1, sensor_msgs::PointField::FLOAT32);
  // For convenience and the xyz, rgb, rgba fields, you can also use the following overloaded function.
  // You have to be aware that the following function does add extra padding for backward compatibility though
  // so it is definitely the solution of choice for PointXYZ and PointXYZRGB
  // 2 is for the number of fields to add
  modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
  // You can then reserve / resize as usual
  modifier.resize(100);

The second set allow you to traverse your PointCloud using an iterator:

  // Define some raw data we'll put in the PointCloud2
  float point_data[] = {1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0};
  uint8_t color_data[] = {40, 80, 120, 160, 200, 240, 20, 40, 60, 80, 100, 120};
  // Define the iterators. When doing so, you define the Field you would like to iterate upon and
  // the type of you would like returned: it is not necessary the type of the PointField as sometimes
  // you pack data in another type (e.g. 3 uchar + 1 uchar for RGB are packed in a float)
  sensor_msgs::PointCloud2Iterator<float> iter_x(cloud_msg, "x");
  sensor_msgs::PointCloud2Iterator<float> iter_y(cloud_msg, "y");
  sensor_msgs::PointCloud2Iterator<float> iter_z(cloud_msg, "z");
  // Even though the r,g,b,a fields do not exist (it's usually rgb, rgba), you can create iterators for
  // those: they will handle data packing for you (in little endian RGB is packed as *,R,G,B in a float
  // and RGBA as A,R,G,B)
  sensor_msgs::PointCloud2Iterator<uint8_t> iter_r(cloud_msg, "r");
  sensor_msgs::PointCloud2Iterator<uint8_t> iter_g(cloud_msg, "g");
  sensor_msgs::PointCloud2Iterator<uint8_t> iter_b(cloud_msg, "b");
  // Fill the PointCloud2
  for(size_t i=0; i<n_points; ++i, ++iter_x, ++iter_y, ++iter_z, ++iter_r, ++iter_g, ++iter_b) {
    *iter_x = point_data[3*i+0];
    *iter_y = point_data[3*i+1];
    *iter_z = point_data[3*i+2];
    *iter_r = color_data[3*i+0];
    *iter_g = color_data[3*i+1];
    *iter_b = color_data[3*i+2];
  }
Author
Radu Bogdan Rusu
Sebastian Pütz

Function Documentation

static void sensor_msgs::clearImage ( Image &  image)
inlinestatic

Definition at line 63 of file fill_image.h.

static bool sensor_msgs::convertPointCloud2ToPointCloud ( const sensor_msgs::PointCloud2 &  input,
sensor_msgs::PointCloud &  output 
)
inlinestatic

Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message.

Parameters
inputthe message in the sensor_msgs::PointCloud2 format
outputthe resultant message in the sensor_msgs::PointCloud format

Definition at line 117 of file point_cloud_conversion.h.

static bool sensor_msgs::convertPointCloudToPointCloud2 ( const sensor_msgs::PointCloud &  input,
sensor_msgs::PointCloud2 &  output 
)
inlinestatic

Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message.

Parameters
inputthe message in the sensor_msgs::PointCloud format
outputthe resultant message in the sensor_msgs::PointCloud2 format

Definition at line 70 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 
)
inlinestatic

Definition at line 44 of file fill_image.h.

static int sensor_msgs::getPointCloud2FieldIndex ( const sensor_msgs::PointCloud2 &  cloud,
const std::string &  field_name 
)
inlinestatic

Get the index of a specified field (i.e., dimension/channel)

Parameters
pointsthe the point cloud message
field_namethe string defining the field name

Definition at line 56 of file point_cloud_conversion.h.

template<int point_field_type, typename T >
T sensor_msgs::readPointCloud2BufferValue ( const unsigned char *  data_ptr)
inline

a value at the given pointer position, interpreted as the datatype specified by the given template argument point_field_type, to the given template type T and returns it.

Parameters
data_ptrpointer into the point cloud 2 buffer
Template Parameters
point_field_typesensor_msgs::PointField datatype value
Treturn type

Definition at line 91 of file point_field_conversion.h.

template<typename T >
T sensor_msgs::readPointCloud2BufferValue ( const unsigned char *  data_ptr,
const unsigned char  datatype 
)
inline

a value at the given pointer position interpreted as the datatype specified by the given datatype parameter to the given template type and returns it.

Parameters
data_ptrpointer into the point cloud 2 buffer
datatypesensor_msgs::PointField datatype value
Template Parameters
Treturn type

Definition at line 104 of file point_field_conversion.h.

template<int point_field_type, typename T >
void sensor_msgs::writePointCloud2BufferValue ( unsigned char *  data_ptr,
value 
)
inline

a given value at the given point position interpreted as the datatype specified by the template argument point_field_type.

Parameters
data_ptrpointer into the point cloud 2 buffer
valuethe value to insert
Template Parameters
point_field_typesensor_msgs::PointField datatype value
Ttype of the value to insert

Definition at line 136 of file point_field_conversion.h.

template<typename T >
void sensor_msgs::writePointCloud2BufferValue ( unsigned char *  data_ptr,
const unsigned char  datatype,
value 
)
inline

a given value at the given point position interpreted as the datatype specified by the given datatype parameter.

Parameters
data_ptrpointer into the point cloud 2 buffer
datatypesensor_msgs::PointField datatype value
valuethe value to insert
Template Parameters
Ttype of the value to insert

Definition at line 150 of file point_field_conversion.h.



sensor_msgs
Author(s):
autogenerated on Fri Jun 7 2019 21:44:16