46 #ifndef SENSOR_MSGS_POINT_FIELD_CONVERSION_H 47 #define SENSOR_MSGS_POINT_FIELD_CONVERSION_H 73 template<>
struct typeAsPointFieldType<int8_t> {
static const uint8_t value = sensor_msgs::PointField::INT8; };
74 template<>
struct typeAsPointFieldType<uint8_t> {
static const uint8_t value = sensor_msgs::PointField::UINT8; };
75 template<>
struct typeAsPointFieldType<int16_t> {
static const uint8_t value = sensor_msgs::PointField::INT16; };
76 template<>
struct typeAsPointFieldType<uint16_t> {
static const uint8_t value = sensor_msgs::PointField::UINT16; };
77 template<>
struct typeAsPointFieldType<int32_t> {
static const uint8_t value = sensor_msgs::PointField::INT32; };
78 template<>
struct typeAsPointFieldType<uint32_t> {
static const uint8_t value = sensor_msgs::PointField::UINT32; };
79 template<>
struct typeAsPointFieldType<float> {
static const uint8_t value = sensor_msgs::PointField::FLOAT32; };
80 template<>
struct typeAsPointFieldType<double> {
static const uint8_t value = sensor_msgs::PointField::FLOAT64; };
90 template<
int po
int_field_type,
typename T>
93 return static_cast<T
>(*(
reinterpret_cast<type
const *
>(data_ptr)));
106 case sensor_msgs::PointField::INT8:
107 return readPointCloud2BufferValue<sensor_msgs::PointField::INT8, T>(data_ptr);
108 case sensor_msgs::PointField::UINT8:
109 return readPointCloud2BufferValue<sensor_msgs::PointField::UINT8, T>(data_ptr);
110 case sensor_msgs::PointField::INT16:
111 return readPointCloud2BufferValue<sensor_msgs::PointField::INT16, T>(data_ptr);
112 case sensor_msgs::PointField::UINT16:
113 return readPointCloud2BufferValue<sensor_msgs::PointField::UINT16, T>(data_ptr);
114 case sensor_msgs::PointField::INT32:
115 return readPointCloud2BufferValue<sensor_msgs::PointField::INT32, T>(data_ptr);
116 case sensor_msgs::PointField::UINT32:
117 return readPointCloud2BufferValue<sensor_msgs::PointField::UINT32, T>(data_ptr);
118 case sensor_msgs::PointField::FLOAT32:
119 return readPointCloud2BufferValue<sensor_msgs::PointField::FLOAT32, T>(data_ptr);
120 case sensor_msgs::PointField::FLOAT64:
121 return readPointCloud2BufferValue<sensor_msgs::PointField::FLOAT64, T>(data_ptr);
135 template<
int po
int_field_type,
typename T>
138 *(
reinterpret_cast<type*
>(data_ptr)) =
static_cast<type
>(value);
152 case sensor_msgs::PointField::INT8:
153 writePointCloud2BufferValue<sensor_msgs::PointField::INT8, T>(data_ptr, value);
155 case sensor_msgs::PointField::UINT8:
156 writePointCloud2BufferValue<sensor_msgs::PointField::UINT8, T>(data_ptr, value);
158 case sensor_msgs::PointField::INT16:
159 writePointCloud2BufferValue<sensor_msgs::PointField::INT16, T>(data_ptr, value);
161 case sensor_msgs::PointField::UINT16:
162 writePointCloud2BufferValue<sensor_msgs::PointField::UINT16, T>(data_ptr, value);
164 case sensor_msgs::PointField::INT32:
165 writePointCloud2BufferValue<sensor_msgs::PointField::INT32, T>(data_ptr, value);
167 case sensor_msgs::PointField::UINT32:
168 writePointCloud2BufferValue<sensor_msgs::PointField::UINT32, T>(data_ptr, value);
170 case sensor_msgs::PointField::FLOAT32:
171 writePointCloud2BufferValue<sensor_msgs::PointField::FLOAT32, T>(data_ptr, value);
173 case sensor_msgs::PointField::FLOAT64:
174 writePointCloud2BufferValue<sensor_msgs::PointField::FLOAT64, T>(data_ptr, value);
void writePointCloud2BufferValue(unsigned char *data_ptr, T value)
Tools for manipulating sensor_msgs.
T readPointCloud2BufferValue(const unsigned char *data_ptr)