00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef _DBW_MKZ_CAN_SONAR_LUT_H
00036 #define _DBW_MKZ_CAN_SONAR_LUT_H
00037 #include <sensor_msgs/PointCloud2.h>
00038 #include <dbw_mkz_msgs/SurroundReport.h>
00039
00040 namespace dbw_mkz_can
00041 {
00042
00043 static const struct {float x; float y; float z; float a;} SONAR_TABLE[] = {
00044
00045 { 4.000, 0.900, 0.100, 0.500 * M_PI},
00046 { 4.000, 0.500, 0.100, 0.100 * M_PI},
00047 { 4.000, 0.200, 0.100, 0.000 * M_PI},
00048 { 4.000, -0.200, 0.100, 0.000 * M_PI},
00049 { 4.000, -0.500, 0.100, 1.900 * M_PI},
00050 { 4.000, -0.900, 0.100, 1.500 * M_PI},
00051 {-1.000, 0.900, 0.100, 0.500 * M_PI},
00052 {-1.000, 0.500, 0.100, 0.900 * M_PI},
00053 {-1.000, 0.200, 0.100, 1.000 * M_PI},
00054 {-1.000, -0.200, 0.100, 1.000 * M_PI},
00055 {-1.000, -0.500, 0.100, 1.100 * M_PI},
00056 {-1.000, -0.900, 0.100, 1.500 * M_PI},
00057 };
00058 static inline float sonarMetersFromBits(uint8_t bits) {
00059 return bits ? ((float)bits * 0.15) + 0.15 : 0.0;
00060 }
00061 static inline uint32_t sonarColorFromRange(float range) {
00062 if (range < 0.7) {
00063 return 0xC0FF0000;
00064 } else if (range < 1.3) {
00065 return 0xC0FFFF00;
00066 } else {
00067 return 0xC000FF00;
00068 }
00069 }
00070 static inline void sonarBuildPointCloud2(sensor_msgs::PointCloud2 &cloud, const dbw_mkz_msgs::SurroundReport &surround) {
00071
00072 const uint32_t POINT_STEP = 16;
00073 cloud.header.frame_id = "base_link";
00074 cloud.header.stamp = surround.header.stamp;
00075 cloud.fields.resize(4);
00076 cloud.fields[0].name = "x";
00077 cloud.fields[0].offset = 0;
00078 cloud.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
00079 cloud.fields[0].count = 1;
00080 cloud.fields[1].name = "y";
00081 cloud.fields[1].offset = 4;
00082 cloud.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
00083 cloud.fields[1].count = 1;
00084 cloud.fields[2].name = "z";
00085 cloud.fields[2].offset = 8;
00086 cloud.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
00087 cloud.fields[2].count = 1;
00088 cloud.fields[3].name = "rgba";
00089 cloud.fields[3].offset = 12;
00090 cloud.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
00091 cloud.fields[3].count = 1;
00092 cloud.data.resize(12 * POINT_STEP);
00093
00094 uint8_t *ptr = cloud.data.data();
00095 for (unsigned int i = 0; i < 12; i++) {
00096 const float range = surround.sonar[i];
00097 if (range > 0.0) {
00098 *((float*)(ptr + 0)) = SONAR_TABLE[i].x + cosf(SONAR_TABLE[i].a) * range;
00099 *((float*)(ptr + 4)) = SONAR_TABLE[i].y + sinf(SONAR_TABLE[i].a) * range;
00100 *((float*)(ptr + 8)) = SONAR_TABLE[i].z;
00101 *((uint32_t*)(ptr + 12)) = sonarColorFromRange(range);
00102 ptr += POINT_STEP;
00103 }
00104 }
00105 if (ptr == cloud.data.data()) {
00106
00107 *((float*)(ptr + 0)) = NAN;
00108 *((float*)(ptr + 4)) = NAN;
00109 *((float*)(ptr + 8)) = NAN;
00110 *((uint32_t*)(ptr + 12)) = 0x00000000;
00111 ptr += POINT_STEP;
00112 }
00113
00114
00115 cloud.point_step = POINT_STEP;
00116 cloud.row_step = ptr - cloud.data.data();
00117 cloud.height = 1;
00118 cloud.width = cloud.row_step / POINT_STEP;
00119 cloud.is_bigendian = false;
00120 cloud.is_dense = true;
00121 cloud.data.resize(cloud.row_step);
00122 }
00123
00124 }
00125
00126 #endif // _DBW_MKZ_CAN_SONAR_LUT_H
00127