radar_object_marker.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2018, SICK AG
00003  * Copyright (C) 2018, Ing.-Buero Dr. Michael Lehning
00004  * Copyright (C) 2016, DFKI GmbH
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 are met:
00009  *
00010  *     * Redistributions of source code must retain the above copyright
00011  *       notice, this list of conditions and the following disclaimer.
00012  *     * Redistributions in binary form must reproduce the above copyright
00013  *       notice, this list of conditions and the following disclaimer in the
00014  *       documentation and/or other materials provided with the distribution.
00015  *     * Neither the name of DFKI GmbH nor the names of its
00016  *       contributors may be used to endorse or promote products derived from
00017  *       this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  *
00031  */
00032 
00033 #include <ros/ros.h>
00034 
00035 #include <visualization_msgs/MarkerArray.h>
00036 #include <sick_scan/RadarScan.h>
00037 
00038 #include <ros/ros.h>
00039 #include <ros/package.h>
00040 #include <math.h>
00041 #include <visualization_msgs/MarkerArray.h>
00042 #include <sick_scan/RadarScan.h>
00043 #include "radar_object_marker/radar_object_marker.h"
00044 #include "pcl_converter/gnuplotPaletteReader.h"
00045 #include <boost/serialization/singleton.hpp>
00046 
00047 float ballRadius = 0.1;
00048 float objectArrowScale = 1.0;
00049 GnuPlotPalette pal;
00050 bool usingPal = false;
00051 
00052 ros::Publisher pub;
00053 ros::Publisher pub_cloud;
00054 
00055 
00056 
00057 
00058 void normalize( float& angle )
00059 {
00060     while ( angle < -M_PI ) angle += (2 * M_PI);
00061     while ( angle >  M_PI ) angle -= (2 * M_PI);
00062 }
00063 
00064 bool isWithinRange( float testAngle, float a, float b )
00065 {
00066     a -= testAngle;
00067     b -= testAngle;
00068     normalize( a );
00069     normalize( b );
00070     if ( a * b >= 0 )
00071         return false; // lying on the same side
00072     return fabs( a - b ) < M_PI;
00073 }
00074 
00075 
00076 
00077 /* check for both directions */
00078 bool checkForAngleInterval(float orgAngle, float* dstAngle, float mainAngle, float mainAngleTol)
00079 {
00080    float tmpAngle;
00081    bool bRet = isWithinRange(orgAngle, mainAngle - mainAngleTol, mainAngle + mainAngleTol);
00082    if (bRet == true)
00083    {
00084        tmpAngle = mainAngle;
00085        normalize(tmpAngle);
00086        *dstAngle = tmpAngle;
00087        return(bRet);
00088    }
00089    bRet = isWithinRange(orgAngle, M_PI + mainAngle - mainAngleTol, M_PI + mainAngle + mainAngleTol);
00090    if (bRet == true)
00091    {
00092        tmpAngle = mainAngle + M_PI;
00093        normalize(tmpAngle);
00094        *dstAngle = tmpAngle;
00095        return(bRet);
00096 
00097    }
00098 
00099 
00100 
00101    return(bRet);
00102 
00103 
00104 
00105 }
00106 
00107 bool checkForAngleIntervalTestbed()
00108 {
00109     bool bRet = false;
00110     double testAngleArrDeg[] = {-161.0, -10.0, -20.0, -30.0, 330.0, 10.0, 20.0, 30.0, -160.0};
00111 
00112     std::vector<double> testAngleArr;
00113 
00114     for ( int i =0; i  < sizeof(testAngleArrDeg)/sizeof(testAngleArrDeg[0]); i++)
00115     {
00116         double tmpAngle = testAngleArrDeg[i] / 180.0 * M_PI;
00117         testAngleArr.push_back(tmpAngle);
00118     }
00119 
00120 
00121     double mainAngle = 20.0/180.0 * M_PI;
00122     double mainAngleTol = 30.0/180.0 * M_PI;
00123     for (int i  = 0; i < testAngleArr.size(); i++)
00124     {
00125         float angle = testAngleArr[i];
00126         float dstAngle;
00127         bRet = checkForAngleInterval(angle, &dstAngle, mainAngle, mainAngleTol);
00128 
00129         printf("Ergebnis: %2d %6.2lf %6.2lf %s\n", i, angle, dstAngle, bRet ? "JA" : "NEIN");
00130     }
00131     return bRet;
00132 }
00133 
00134 
00135 
00136 void callback(const sick_scan::RadarScan::ConstPtr &oa)
00137   {
00138   RadarObjectMarkerCfg *cfgPtr = &boost::serialization::singleton<RadarObjectMarkerCfg>::get_mutable_instance();
00139 
00140   enum TARGET_MARKER_TYPE {TARGET_MARKER_BALL, TARGET_MARKER_ARROW, TARGET_MARKER_NUM};
00141   visualization_msgs::MarkerArray rawTargetArray[TARGET_MARKER_NUM];  // ball and arrow
00142   sensor_msgs::PointCloud2 cloud_msg;
00143 
00144   for (int i = 0; i < TARGET_MARKER_NUM; i++)
00145   {
00146     rawTargetArray[i].markers.resize(oa->targets.width);
00147   }
00148 
00149   int coordIdx[3] = {0};
00150   int vradIdx = -1;
00151   int amplitudeIdx = -1;
00152 
00153   for (int i = 0; i < 3; i++)
00154   {
00155     coordIdx[i] = -1;
00156   }
00157 
00158 
00159   bool useCurrTimeStamp = true;
00160   ros::Time  currTimeStamp = ros::Time::now();  // timestamp incoming package, will be overwritten by get_datagram
00161   for (int i = 0; i < oa->targets.fields.size(); i++)
00162   {
00163     std::string fieldName = oa->targets.fields[i].name;
00164     // x,y,z, vrad, amplitude
00165     if (fieldName.compare("x") == 0)
00166     {
00167       coordIdx[0] = i;
00168     }
00169     if (fieldName.compare("y") == 0)
00170     {
00171       coordIdx[1] = i;
00172     }
00173     if (fieldName.compare("z") == 0)
00174     {
00175       coordIdx[2] = i;
00176     }
00177     if (fieldName.compare("vrad") == 0)
00178     {
00179       vradIdx = i;
00180     }
00181     if (fieldName.compare("amplitude") == 0)
00182     {
00183       amplitudeIdx = i;
00184     }
00185 
00186     // printf("%s\n", fieldName.c_str());
00187   }
00188 
00189   int numRawTargets = oa->targets.width;
00190 
00191   if (numRawTargets > 0)
00192   {
00193     cloud_msg.header = oa->header;
00194 
00195     if (useCurrTimeStamp)
00196     {
00197       cloud_msg.header.stamp = currTimeStamp;
00198     }
00199 
00200     cloud_msg.height = oa->targets.height;
00201     cloud_msg.width  = oa->targets.width;
00202     cloud_msg.row_step = oa->targets.row_step;
00203     cloud_msg.point_step = oa->targets.point_step;
00204     cloud_msg.data = oa->targets.data;
00205     cloud_msg.fields  = oa->targets.fields;
00206     cloud_msg.is_dense = oa->targets.is_dense;
00207     cloud_msg.is_bigendian = oa->targets.is_bigendian;
00208     pub_cloud.publish(cloud_msg);
00209   }
00210   for (size_t i = 0; i < oa->targets.width; i++)
00211   {
00212     int tmpId = i;
00213     float ampl = 0.0;
00214     float xs, ys;
00215     float pts3d[3];
00216     float vrad = 0.0;
00217     for (int ii = 0; ii < 3; ii++)
00218     {
00219       if (coordIdx[ii] != -1)
00220       {
00221         int tmpIdx = coordIdx[ii];
00222         float *valPtr = (float *) (&(oa->targets.data[0]) + i * oa->targets.point_step +
00223                                    oa->targets.fields[tmpIdx].offset);
00224         pts3d[ii] = *valPtr;
00225       }
00226     }
00227     if (vradIdx != -1)
00228     {
00229       int tmpIdx = vradIdx;
00230       float *valPtr = (float *) (&(oa->targets.data[0]) + i * oa->targets.point_step +
00231                                  oa->targets.fields[tmpIdx].offset);
00232       vrad = *valPtr;
00233     }
00234     if (amplitudeIdx)
00235     {
00236       int tmpIdx = amplitudeIdx;
00237       float *valPtr = (float *) (&(oa->targets.data[0]) + i * oa->targets.point_step +
00238                                  oa->targets.fields[tmpIdx].offset);
00239       ampl = *valPtr;
00240 
00241     }
00242 
00243     for (int iLoop = 0; iLoop < TARGET_MARKER_NUM; iLoop++)
00244     {
00245 
00246       rawTargetArray[iLoop].markers[i].header = oa->header;
00247 
00248       if (useCurrTimeStamp)
00249       {
00250         rawTargetArray[iLoop].markers[i].header.stamp = currTimeStamp;
00251       }
00252 
00253       rawTargetArray[iLoop].markers[i].ns = "rawtargets";
00254       rawTargetArray[iLoop].markers[i].id = tmpId + iLoop * numRawTargets;
00255       switch (iLoop)
00256       {
00257         case TARGET_MARKER_ARROW:
00258         {
00259           rawTargetArray[iLoop].markers[i].type = visualization_msgs::Marker::ARROW;
00260           rawTargetArray[iLoop].markers[i].scale.x = 0.1;
00261           rawTargetArray[iLoop].markers[i].scale.y = 0.2;
00262 
00263           rawTargetArray[iLoop].markers[i].points.resize(2);
00264           rawTargetArray[iLoop].markers[i].points[0].x = pts3d[0];
00265           rawTargetArray[iLoop].markers[i].points[0].y = pts3d[1];
00266           rawTargetArray[iLoop].markers[i].points[0].z = pts3d[2];
00267           float lineOfSight = atan2(pts3d[1], pts3d[0]);
00268           rawTargetArray[iLoop].markers[i].points[1].x = pts3d[0] + cos(lineOfSight) * vrad * 0.1;
00269           rawTargetArray[iLoop].markers[i].points[1].y = pts3d[1] + sin(lineOfSight) * vrad * 0.1;
00270           rawTargetArray[iLoop].markers[i].points[1].z = pts3d[2];
00271 
00272         }
00273           break;
00274         case TARGET_MARKER_BALL:
00275           rawTargetArray[iLoop].markers[i].type = visualization_msgs::Marker::SPHERE;
00276           rawTargetArray[iLoop].markers[i].scale.x = ballRadius;
00277           rawTargetArray[iLoop].markers[i].scale.y = ballRadius;
00278           rawTargetArray[iLoop].markers[i].scale.z = ballRadius;
00279 
00280 
00281           rawTargetArray[iLoop].markers[i].pose.position.x = pts3d[0];
00282           rawTargetArray[iLoop].markers[i].pose.position.y = pts3d[1];
00283           rawTargetArray[iLoop].markers[i].pose.position.z = pts3d[2];
00284           rawTargetArray[iLoop].markers[i].pose.orientation.x = 0.0;
00285           rawTargetArray[iLoop].markers[i].pose.orientation.y = 0.0;
00286           rawTargetArray[iLoop].markers[i].pose.orientation.z = 0.0;
00287           rawTargetArray[iLoop].markers[i].pose.orientation.w = 1.0;
00288           break;
00289 
00290       }
00291       rawTargetArray[iLoop].markers[i].action = visualization_msgs::Marker::ADD;
00292       if (cfgPtr->isPaletteUsed())
00293       {
00294           GnuPlotPalette pal = cfgPtr->getGnuPlotPalette();
00295          float idxRange = ampl - cfgPtr->getPaletteMinAmpl();
00296          double rangeAmpl = cfgPtr->getPaletteMaxAmpl() - cfgPtr->getPaletteMinAmpl();
00297          idxRange /= rangeAmpl;
00298          if (idxRange < 0.0)
00299          {
00300            idxRange = 0.0;
00301          }
00302          if (idxRange > 1.0)
00303          {
00304           idxRange = 1.0;
00305          }
00306          unsigned char greyIdx = (unsigned char)(255.999 * idxRange);
00307          unsigned char red = pal.getRbgValue(greyIdx, 0U);
00308          unsigned char green = pal.getRbgValue(greyIdx, 1U);
00309          unsigned char blue = pal.getRbgValue(greyIdx, 2U);
00310 
00311          float redF, greenF, blueF;
00312         redF = red / 255.00;
00313         greenF = green / 255.00;
00314         blueF = blue / 255.00;
00315         rawTargetArray[iLoop].markers[i].color.a = 0.75;
00316         rawTargetArray[iLoop].markers[i].color.r = redF;
00317         rawTargetArray[iLoop].markers[i].color.g = greenF;
00318         rawTargetArray[iLoop].markers[i].color.b = blueF;
00319       }
00320       else{
00321       rawTargetArray[iLoop].markers[i].color.a = 0.75;
00322       rawTargetArray[iLoop].markers[i].color.r = GLASBEY_LUT[tmpId * 3] / 255.0;
00323       rawTargetArray[iLoop].markers[i].color.g = GLASBEY_LUT[tmpId * 3 + 1] / 255.0;
00324       rawTargetArray[iLoop].markers[i].color.b = GLASBEY_LUT[tmpId * 3 + 2] / 255.0;
00325       }
00326       rawTargetArray[iLoop].markers[i].lifetime = ros::Duration(0.5);
00327 
00328 
00329     }
00330   }
00331 
00332   for (int iLoop = 0; iLoop < TARGET_MARKER_NUM; iLoop++)
00333   {
00334     pub.publish(rawTargetArray[iLoop]);
00335   }
00336 
00337   /***********************************************************************
00338    *
00339    *
00340    * Drawing marker for objects
00341    *
00342    ***********************************************************************
00343    */
00344   visualization_msgs::MarkerArray object_boxes;
00345   object_boxes.markers.resize(2 * oa->objects.size());
00346 
00347   visualization_msgs::MarkerArray object_labels;
00348   object_labels.markers.resize(1 * oa->objects.size());
00349 
00350   float vp_dir = 0.0;
00351   float vp_dir_deg = 0.0;
00352 
00353   double angleMainDirDeg = 20;
00354   double angleMainDir = angleMainDirDeg / 180.0 * M_PI;
00355   double angleMainDirTolDeg = 20.0;
00356   double angleMainDirTol = angleMainDirTolDeg / 180.0 * M_PI;
00357 
00358   std::vector<float> vehiclePredefinedDir;
00359   std::vector<float> vehicleAbsoluteSpeed;
00360   std::vector<bool>  vehicleIsInPredefinedDir;
00361 
00362   int objNum = oa->objects.size();
00363 
00364   vehiclePredefinedDir.resize(objNum);
00365   vehicleIsInPredefinedDir.resize(objNum);  // flag arraw whether the vehicle drives in tihs dir. or not
00366   vehicleAbsoluteSpeed.resize(objNum);
00367 
00368   for (int iLoop = 0; iLoop < 2; iLoop++)
00369   {
00370     for (size_t i = 0; i < oa->objects.size(); i++)
00371     {
00372         int colorId = oa->objects[i].id % 256;
00373         float vp[3];
00374         vp[0] = oa->objects[i].velocity.twist.linear.x;
00375         vp[1] = oa->objects[i].velocity.twist.linear.y;
00376         vp[2] = oa->objects[i].velocity.twist.linear.z;
00377         float vabs = sqrt(vp[0] * vp[0] + vp[1]*vp[1] + vp[2]*vp[2]);
00378         vehicleAbsoluteSpeed[i] = vabs;
00379         vp_dir = atan2(vp[1], vp[0]);
00380         vp_dir_deg = vp_dir / 3.141592 * 180.0;
00381         float dstAngle;
00382 
00383         bool bRet = checkForAngleInterval(vp_dir, &dstAngle, angleMainDir, angleMainDirTol);
00384         vehiclePredefinedDir[i] = dstAngle;
00385         vehicleIsInPredefinedDir[i] = bRet;
00386 
00387       int idx = i + iLoop * oa->objects.size();
00388       int tmpId = i; // better: oa->objects[i].id;
00389       object_boxes.markers[idx].header = oa->header;
00390 
00391       if (useCurrTimeStamp)
00392       {
00393         object_boxes.markers[idx].header.stamp = currTimeStamp;
00394       }
00395       std::string nameSpaceBoxes = "object_boxes_slow";
00396       if (vabs > 5.0)
00397       {
00398           nameSpaceBoxes = "object_boxes_fast";
00399       }
00400       object_boxes.markers[idx].ns = nameSpaceBoxes;
00401       object_boxes.markers[idx].id = tmpId + iLoop * oa->objects.size(); // i; // oa->objects[i].id;
00402       object_boxes.markers[idx].action = visualization_msgs::Marker::ADD;
00403       object_boxes.markers[idx].color.a = 0.75;
00404       object_boxes.markers[idx].color.r = GLASBEY_LUT[colorId * 3] / 255.0;
00405       object_boxes.markers[idx].color.g = GLASBEY_LUT[colorId * 3 + 1] / 255.0;
00406       object_boxes.markers[idx].color.b = GLASBEY_LUT[colorId * 3 + 2] / 255.0;
00407       object_boxes.markers[idx].lifetime = ros::Duration(1.0);
00408 
00409       if (iLoop == 0)
00410       {
00411           object_labels.markers[i].header = oa->header;
00412           if (useCurrTimeStamp)
00413           {
00414               if (iLoop == 0) {
00415                   object_labels.markers[i].header.stamp = currTimeStamp;
00416               }
00417           }
00418 
00419           object_labels.markers[i].id = tmpId + iLoop * oa->objects.size(); // i; // oa->objects[i].id;
00420           object_labels.markers[i].action = visualization_msgs::Marker::ADD;
00421           object_labels.markers[i].color.a = 0.75;
00422           object_labels.markers[i].color.r = GLASBEY_LUT[colorId * 3] / 255.0;
00423           object_labels.markers[i].color.g = GLASBEY_LUT[colorId * 3 + 1] / 255.0;
00424           object_labels.markers[i].color.b = GLASBEY_LUT[colorId * 3 + 2] / 255.0;
00425           object_labels.markers[i].lifetime = ros::Duration(1.0);
00426 
00427           object_labels.markers[i].type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00428           object_labels.markers[i].pose = oa->objects[i].object_box_center.pose;
00429           object_labels.markers[i].scale.z = 1.0;
00430 
00431           {
00432 
00433               char szLabel[255];
00434               sprintf(szLabel,"%5.1lf [m/s]", vabs );
00435 
00436               if (vabs > 10.0)
00437               {
00438               // printf("Dir: %8.3lf [deg]\n", vp_dir_deg);
00439               }
00440               std::string object_label_ns = "???";
00441               if (vabs > 5.0) // 18 km/h
00442               {
00443                   object_label_ns = "object_label_fast";
00444               }
00445               else
00446               {
00447                   object_label_ns = "object_label_slow";
00448 
00449               }
00450               object_labels.markers[i].text = szLabel;
00451               object_labels.markers[i].ns = object_label_ns;
00452 
00453               if (vehicleIsInPredefinedDir[i] == false)
00454               {
00455                   object_labels.markers[i].scale.z = 0.00;
00456               }
00457           }
00458 
00459 
00460       }
00461 
00462       /* object box center is the reference ...
00463        * */
00464       object_boxes.markers[idx].pose = oa->objects[i].object_box_center.pose;  // Position and Orientation
00465       object_boxes.markers[idx].scale = oa->objects[i].object_box_size;
00466 
00467       switch (iLoop)
00468       {
00469         case 0:  // Drawing object cubes
00470           object_boxes.markers[idx].type = visualization_msgs::Marker::CUBE;
00471           object_boxes.markers[idx].pose.position.z  +=  oa->objects[i].object_box_size.z * 0.5;
00472 
00473 
00474           break;
00475         case 1:
00476           object_boxes.markers[idx].type = visualization_msgs::Marker::ARROW;
00477 
00478           break;
00479       }
00480 
00481       switch (iLoop)
00482       {
00483         case 0:
00484           if (object_boxes.markers[idx].scale.x == 0.0)
00485           {
00486             object_boxes.markers[idx].scale.x = 0.01;
00487           }
00488           if (object_boxes.markers[idx].scale.y == 0.0)
00489           {
00490             object_boxes.markers[idx].scale.y = 0.01;
00491           }
00492           if (object_boxes.markers[idx].scale.z == 0.0)
00493           {
00494             object_boxes.markers[idx].scale.z = 0.01;
00495           }
00496 
00497           if (vehicleIsInPredefinedDir[i] == false) {
00498               object_boxes.markers[idx].scale.x = 0.0;
00499               object_boxes.markers[idx].scale.y = 0.0;
00500               object_boxes.markers[idx].scale.z = 0.0;
00501               object_boxes.markers[idx].lifetime = ros::Duration(0.001);
00502           } else{
00503 
00504 
00505               if (vehicleIsInPredefinedDir[i] == true)
00506               {
00507                   float theta = vehiclePredefinedDir[i];
00508 
00509 
00510                   // Falls wir eine Zwangsrichtung einpraegen wollen, dann muessen wir es am besten hier tun.
00511 
00512               // (n_x, n_y, n_z) = (0, 0, 1), so (x, y, z, w) = (0, 0, sin(theta/2), cos(theta/2)).
00513               // see https://answers.ros.org/question/9772/quaternions-orientation-representation/
00514                   float theta2 = 0.5  * theta;
00515                   object_boxes.markers[idx].pose.orientation.z = sin(theta2);
00516                   object_boxes.markers[idx].pose.orientation.w = cos(theta2);
00517 
00518               }
00519 
00520 
00521           }
00522           break;
00523         case 1:
00524         {
00525           float xTmp;
00526           float yTmp;
00527 
00528           object_boxes.markers[idx].scale.x = 0.5;
00529           object_boxes.markers[idx].scale.y = 0.5;
00530           object_boxes.markers[idx].scale.z = 0.5;
00531 
00532 
00533 
00534 /*          float cosVal =  oa->objects[i].object_box_center.pose.orientation.x;
00535           float sinVal =  oa->objects[i].object_box_center.pose.orientation.y;
00536 */
00537           xTmp = oa->objects[i].object_box_center.pose.position.x;
00538           yTmp = oa->objects[i].object_box_center.pose.position.y;
00539 
00540           double vehLen = oa->objects[i].object_box_size.x;
00541 
00542 
00543           float quaternion[4] = {0};
00544           // rotation around z-axis: [cos(theta/2.0), 0, 0, sin(theta/2.0) ]
00545           quaternion[0] = oa->objects[i].object_box_center.pose.orientation.x;
00546           quaternion[1] = oa->objects[i].object_box_center.pose.orientation.y;
00547           quaternion[2] = oa->objects[i].object_box_center.pose.orientation.z;
00548           quaternion[3] = oa->objects[i].object_box_center.pose.orientation.w;
00549 
00550 
00551           // Falls wir eine Zwangsrichtung einpraegen wollen, dann muessen wir es am besten hier tun.
00552 
00553           // (n_x, n_y, n_z) = (0, 0, 1), so (x, y, z, w) = (0, 0, sin(theta/2), cos(theta/2)).
00554           // see https://answers.ros.org/question/9772/quaternions-orientation-representation/
00555           float theta2 = atan2(quaternion[2], quaternion[3]);
00556           float theta = 2.0f * theta2;
00557           if (vehicleIsInPredefinedDir[i] == true)
00558           {
00559                 theta = vehiclePredefinedDir[i];
00560           }
00561 
00562           float cosVal = cos(theta);
00563           float sinVal = sin(theta);
00564           xTmp += cosVal * vehLen * 0.5;
00565           yTmp += sinVal * vehLen * 0.5;
00566           object_boxes.markers[idx].pose.position.x = xTmp;
00567           object_boxes.markers[idx].pose.position.y = yTmp;
00568           object_boxes.markers[idx].pose.position.z = 0.0;
00569 
00570           // oa->objects[i].object_box_center.pose.orientation;
00571           // Arrow orientation is already rotated
00572           object_boxes.markers[idx].pose.orientation.x = 0.0;
00573           object_boxes.markers[idx].pose.orientation.y = 0.0;
00574           object_boxes.markers[idx].pose.orientation.z = 0.0;
00575           object_boxes.markers[idx].pose.orientation.w = 0.0;
00576 
00577           object_boxes.markers[idx].points.resize(2);
00578           object_boxes.markers[idx].points[0].x = 0.0;
00579           object_boxes.markers[idx].points[0].y = 0.0;
00580           object_boxes.markers[idx].points[0].z = 0.0;
00581 
00582           float absSpeed = 0.0;
00583           for (int j = 0; j < 3; j++)
00584           {
00585             float speedPartial = 0.0;
00586             switch(j)
00587             {
00588               case 0: speedPartial = oa->objects[i].velocity.twist.linear.x; break;
00589               case 1: speedPartial = oa->objects[i].velocity.twist.linear.y; break;
00590               case 2: speedPartial = oa->objects[i].velocity.twist.linear.z; break;
00591             }
00592             absSpeed += speedPartial * speedPartial;
00593           }
00594           absSpeed = sqrt(absSpeed);
00595           double lengthOfArrow = objectArrowScale * absSpeed;
00596           if (objectArrowScale < 0.0)
00597           {
00598             lengthOfArrow = -objectArrowScale;  // if scale is negative take its absolute value as length of arrow in [m]
00599           }
00600           // lengthOfArrow = 5.0;
00601 
00602           if (vehicleIsInPredefinedDir[i] == false) {
00603               object_boxes.markers[idx].lifetime = ros::Duration(0.001);
00604               lengthOfArrow = 0.0;
00605           }
00606           object_boxes.markers[idx].points[1].x = 0.0 + lengthOfArrow * cosVal;
00607           object_boxes.markers[idx].points[1].y = 0.0 + lengthOfArrow * sinVal;
00608           object_boxes.markers[idx].points[1].z = 0.0;
00609           // pub.publish(object_boxes);
00610 
00611         }
00612           break;
00613       }
00614 
00615       // printf("Idx: %2d X: %8.3lf Y: %8.3lf\n", idx, object_boxes.markers[idx].pose.position.x, object_boxes.markers[idx].pose.position.y);
00616     }
00617   }
00618   pub.publish(object_boxes);
00619   pub.publish(object_labels);
00620 
00621   }
00622 
00623 
00624   int main(int argc, char **argv)
00625   {
00626     // checkForAngleIntervalTestbed();
00627     ROS_INFO("radar_object_marker, compiled at [%s] [%s]", __DATE__, __TIME__);
00628     RadarObjectMarkerCfg *cfgPtr = &boost::serialization::singleton<RadarObjectMarkerCfg>::get_mutable_instance();
00629     ros::init(argc, argv, "radar_object_marker");
00630     ros::NodeHandle nh;
00631     ros::NodeHandle nhPriv("~");
00632 
00633     std::string heatMap;
00634     double minAmpl = 10.0;
00635     double maxAmpl = 90.0;
00636     bool paramRes = nhPriv.getParam("rawtarget_sphere_radius", ballRadius);
00637     paramRes = nhPriv.getParam("rawtarget_palette_name", heatMap);
00638     paramRes = nhPriv.getParam("rawtarget_palette_min_ampl", minAmpl);
00639     paramRes = nhPriv.getParam("rawtarget_palette_max_ampl", maxAmpl);
00640 
00641     paramRes = nhPriv.getParam("object_arrow_scale", objectArrowScale);
00642 
00643     cfgPtr->setPaletteName(heatMap);
00644     cfgPtr->setPaletteMinAmpl(minAmpl);
00645     cfgPtr->setPaletteMaxAmpl(maxAmpl);
00646 
00647 
00648 
00649     std::string path = ros::package::getPath("sick_scan");
00650 
00651     if (cfgPtr->getPaletteName().length() > 0)
00652     {
00653       std::string heatMapFileName = path + "/config/" + cfgPtr->getPaletteName();
00654       pal.load(heatMapFileName);
00655       usingPal = true;
00656       cfgPtr->setGnuPlotPalette(pal);
00657       cfgPtr->setPaletteUsed(true);
00658     }
00659     else
00660     {
00661       cfgPtr->setPaletteUsed(false);
00662     }
00663 
00664     ROS_INFO("Subscribing to radar and pulishing to radar_markers");
00665 
00666     ros::Subscriber sub = nh.subscribe("radar", 1, callback);
00667     pub = nh.advertise<visualization_msgs::MarkerArray>("radar_markers", 1);
00668 
00669     pub_cloud =  nh.advertise<sensor_msgs::PointCloud2>("radar_cloud", 1);
00670 
00671     ros::spin();
00672 
00673     return 0;
00674     }


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Tue Jul 9 2019 05:05:34