sonar_lut.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015-2019, Dataspeed Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Dataspeed Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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 //   x,      y,     z,     angle
00045  { 4.000,  0.900, 0.100, 0.500 * M_PI}, // Front left side
00046  { 4.000,  0.500, 0.100, 0.100 * M_PI}, // Front left corner
00047  { 4.000,  0.200, 0.100, 0.000 * M_PI}, // Front left center
00048  { 4.000, -0.200, 0.100, 0.000 * M_PI}, // Front right center
00049  { 4.000, -0.500, 0.100, 1.900 * M_PI}, // Front right corner
00050  { 4.000, -0.900, 0.100, 1.500 * M_PI}, // Front right side
00051  {-1.000,  0.900, 0.100, 0.500 * M_PI}, // Rear left side
00052  {-1.000,  0.500, 0.100, 0.900 * M_PI}, // Rear left corner
00053  {-1.000,  0.200, 0.100, 1.000 * M_PI}, // Rear left center
00054  {-1.000, -0.200, 0.100, 1.000 * M_PI}, // Rear right center
00055  {-1.000, -0.500, 0.100, 1.100 * M_PI}, // Rear right corner
00056  {-1.000, -0.900, 0.100, 1.500 * M_PI}, // Rear right side
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; // rgba = RED
00064   } else if (range < 1.3) {
00065     return 0xC0FFFF00; // rgba = YELLOW
00066   } else {
00067     return 0xC000FF00; // rgba = GREEN
00068   }
00069 }
00070 static inline void sonarBuildPointCloud2(sensor_msgs::PointCloud2 &cloud, const dbw_mkz_msgs::SurroundReport &surround) {
00071   // Populate message fields
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; // x
00099       *((float*)(ptr + 4)) = SONAR_TABLE[i].y + sinf(SONAR_TABLE[i].a) * range; // y
00100       *((float*)(ptr + 8)) = SONAR_TABLE[i].z; // z
00101       *((uint32_t*)(ptr + 12)) = sonarColorFromRange(range); // rgba
00102       ptr += POINT_STEP;
00103     }
00104   }
00105   if (ptr == cloud.data.data()) {
00106     // Prevent rviz from latching the last message
00107     *((float*)(ptr + 0)) = NAN; // x
00108     *((float*)(ptr + 4)) = NAN; // y
00109     *((float*)(ptr + 8)) = NAN; // z
00110     *((uint32_t*)(ptr + 12)) = 0x00000000; // rgba
00111     ptr += POINT_STEP;
00112   }
00113 
00114   // Populate message with number of valid points
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); // Shrink to actual size
00122 }
00123 
00124 } // namespace dbw_mkz_can
00125 
00126 #endif // _DBW_MKZ_CAN_SONAR_LUT_H
00127 


dbw_mkz_can
Author(s): Kevin Hallenbeck
autogenerated on Thu Jul 4 2019 20:08:17