47 #ifndef SENSOR_MSGS_POINT_FIELD_CONVERSION_H
48 #define SENSOR_MSGS_POINT_FIELD_CONVERSION_H
60 template<
int>
struct pointFieldTypeAsType {};
73 template<
typename T>
struct typeAsPointFieldType {};
91 template<
int po
int_field_type,
typename T>
94 return static_cast<T
>(*(
reinterpret_cast<type const *
>(data_ptr)));
108 return readPointCloud2BufferValue<sensor_msgs::PointField::INT8, T>(data_ptr);
110 return readPointCloud2BufferValue<sensor_msgs::PointField::UINT8, T>(data_ptr);
112 return readPointCloud2BufferValue<sensor_msgs::PointField::INT16, T>(data_ptr);
114 return readPointCloud2BufferValue<sensor_msgs::PointField::UINT16, T>(data_ptr);
116 return readPointCloud2BufferValue<sensor_msgs::PointField::INT32, T>(data_ptr);
118 return readPointCloud2BufferValue<sensor_msgs::PointField::UINT32, T>(data_ptr);
120 return readPointCloud2BufferValue<sensor_msgs::PointField::FLOAT32, T>(data_ptr);
122 return readPointCloud2BufferValue<sensor_msgs::PointField::FLOAT64, T>(data_ptr);
134 template<
int po
int_field_type,
typename T>
137 *(
reinterpret_cast<type*
>(data_ptr)) =
static_cast<type>(value);
152 writePointCloud2BufferValue<sensor_msgs::PointField::INT8, T>(data_ptr, value);
155 writePointCloud2BufferValue<sensor_msgs::PointField::UINT8, T>(data_ptr, value);
158 writePointCloud2BufferValue<sensor_msgs::PointField::INT16, T>(data_ptr, value);
161 writePointCloud2BufferValue<sensor_msgs::PointField::UINT16, T>(data_ptr, value);
164 writePointCloud2BufferValue<sensor_msgs::PointField::INT32, T>(data_ptr, value);
167 writePointCloud2BufferValue<sensor_msgs::PointField::UINT32, T>(data_ptr, value);
170 writePointCloud2BufferValue<sensor_msgs::PointField::FLOAT32, T>(data_ptr, value);
173 writePointCloud2BufferValue<sensor_msgs::PointField::FLOAT64, T>(data_ptr, value);