35 #ifndef _DBW_MKZ_CAN_SONAR_LUT_H 36 #define _DBW_MKZ_CAN_SONAR_LUT_H 37 #include <sensor_msgs/PointCloud2.h> 38 #include <dbw_mkz_msgs/SurroundReport.h> 45 { 4.000, 0.900, 0.100, 0.500 * M_PI},
46 { 4.000, 0.500, 0.100, 0.100 * M_PI},
47 { 4.000, 0.200, 0.100, 0.000 * M_PI},
48 { 4.000, -0.200, 0.100, 0.000 * M_PI},
49 { 4.000, -0.500, 0.100, 1.900 * M_PI},
50 { 4.000, -0.900, 0.100, 1.500 * M_PI},
51 {-1.000, 0.900, 0.100, 0.500 * M_PI},
52 {-1.000, 0.500, 0.100, 0.900 * M_PI},
53 {-1.000, 0.200, 0.100, 1.000 * M_PI},
54 {-1.000, -0.200, 0.100, 1.000 * M_PI},
55 {-1.000, -0.500, 0.100, 1.100 * M_PI},
56 {-1.000, -0.900, 0.100, 1.500 * M_PI},
59 return bits ? ((float)bits * 0.15) + 0.15 : 0.0;
64 }
else if (range < 1.3) {
70 static inline void sonarBuildPointCloud2(sensor_msgs::PointCloud2 &cloud,
const dbw_mkz_msgs::SurroundReport &surround) {
72 const uint32_t POINT_STEP = 16;
73 cloud.header.frame_id =
"base_link";
74 cloud.header.stamp = surround.header.stamp;
75 cloud.fields.resize(4);
76 cloud.fields[0].name =
"x";
77 cloud.fields[0].offset = 0;
78 cloud.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
79 cloud.fields[0].count = 1;
80 cloud.fields[1].name =
"y";
81 cloud.fields[1].offset = 4;
82 cloud.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
83 cloud.fields[1].count = 1;
84 cloud.fields[2].name =
"z";
85 cloud.fields[2].offset = 8;
86 cloud.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
87 cloud.fields[2].count = 1;
88 cloud.fields[3].name =
"rgba";
89 cloud.fields[3].offset = 12;
90 cloud.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
91 cloud.fields[3].count = 1;
92 cloud.data.resize(12 * POINT_STEP);
94 uint8_t *ptr = cloud.data.data();
95 for (
unsigned int i = 0; i < 12; i++) {
96 const float range = surround.sonar[i];
105 if (ptr == cloud.data.data()) {
107 *((
float*)(ptr + 0)) = NAN;
108 *((
float*)(ptr + 4)) = NAN;
109 *((
float*)(ptr + 8)) = NAN;
110 *((uint32_t*)(ptr + 12)) = 0x00000000;
115 cloud.point_step = POINT_STEP;
116 cloud.row_step = ptr - cloud.data.data();
118 cloud.width = cloud.row_step / POINT_STEP;
119 cloud.is_bigendian =
false;
120 cloud.is_dense =
true;
121 cloud.data.resize(cloud.row_step);
126 #endif // _DBW_MKZ_CAN_SONAR_LUT_H
static float sonarMetersFromBits(uint8_t bits)
static const struct dbw_mkz_can::@18 SONAR_TABLE[]
static void sonarBuildPointCloud2(sensor_msgs::PointCloud2 &cloud, const dbw_mkz_msgs::SurroundReport &surround)
static uint32_t sonarColorFromRange(float range)