35 #include <visualization_msgs/MarkerArray.h>
36 #include <sick_scan/RadarScan.h>
41 #include <visualization_msgs/MarkerArray.h>
42 #include <sick_scan/RadarScan.h>
45 #include <boost/serialization/singleton.hpp>
72 return fabs( a - b ) < M_PI;
81 bool bRet =
isWithinRange(orgAngle, mainAngle - mainAngleTol, mainAngle + mainAngleTol);
89 bRet =
isWithinRange(orgAngle, M_PI + mainAngle - mainAngleTol, M_PI + mainAngle + mainAngleTol);
92 tmpAngle = mainAngle + M_PI;
110 double testAngleArrDeg[] = {-161.0, -10.0, -20.0, -30.0, 330.0, 10.0, 20.0, 30.0, -160.0};
112 std::vector<double> testAngleArr;
114 for (
int i =0; i <
sizeof(testAngleArrDeg)/
sizeof(testAngleArrDeg[0]); i++)
116 double tmpAngle = testAngleArrDeg[i] / 180.0 * M_PI;
117 testAngleArr.push_back(tmpAngle);
121 double mainAngle = 20.0/180.0 * M_PI;
122 double mainAngleTol = 30.0/180.0 * M_PI;
123 for (
int i = 0; i < testAngleArr.size(); i++)
125 float angle = testAngleArr[i];
129 printf(
"Ergebnis: %2d %6.2lf %6.2lf %s\n", i,
angle, dstAngle, bRet ?
"JA" :
"NEIN");
136 void callback(
const sick_scan::RadarScan::ConstPtr &oa)
138 RadarObjectMarkerCfg *cfgPtr = &boost::serialization::singleton<RadarObjectMarkerCfg>::get_mutable_instance();
140 enum TARGET_MARKER_TYPE {TARGET_MARKER_BALL, TARGET_MARKER_ARROW, TARGET_MARKER_NUM};
141 visualization_msgs::MarkerArray rawTargetArray[TARGET_MARKER_NUM];
142 sensor_msgs::PointCloud2 cloud_msg;
144 for (
int i = 0; i < TARGET_MARKER_NUM; i++)
146 rawTargetArray[i].markers.resize(oa->targets.width);
149 int coordIdx[3] = {0};
151 int amplitudeIdx = -1;
153 for (
int i = 0; i < 3; i++)
159 bool useCurrTimeStamp =
true;
161 for (
int i = 0; i < oa->targets.fields.size(); i++)
163 std::string fieldName = oa->targets.fields[i].name;
165 if (fieldName.compare(
"x") == 0)
169 if (fieldName.compare(
"y") == 0)
173 if (fieldName.compare(
"z") == 0)
177 if (fieldName.compare(
"vrad") == 0)
181 if (fieldName.compare(
"amplitude") == 0)
189 int numRawTargets = oa->targets.width;
191 if (numRawTargets > 0)
193 cloud_msg.header = oa->header;
195 if (useCurrTimeStamp)
197 cloud_msg.header.stamp = currTimeStamp;
200 cloud_msg.height = oa->targets.height;
201 cloud_msg.width = oa->targets.width;
202 cloud_msg.row_step = oa->targets.row_step;
203 cloud_msg.point_step = oa->targets.point_step;
204 cloud_msg.data = oa->targets.data;
205 cloud_msg.fields = oa->targets.fields;
206 cloud_msg.is_dense = oa->targets.is_dense;
207 cloud_msg.is_bigendian = oa->targets.is_bigendian;
210 for (
size_t i = 0; i < oa->targets.width; i++)
217 for (
int ii = 0; ii < 3; ii++)
219 if (coordIdx[ii] != -1)
221 int tmpIdx = coordIdx[ii];
222 float *valPtr = (
float *) (&(oa->targets.data[0]) + i * oa->targets.point_step +
223 oa->targets.fields[tmpIdx].offset);
229 int tmpIdx = vradIdx;
230 float *valPtr = (
float *) (&(oa->targets.data[0]) + i * oa->targets.point_step +
231 oa->targets.fields[tmpIdx].offset);
236 int tmpIdx = amplitudeIdx;
237 float *valPtr = (
float *) (&(oa->targets.data[0]) + i * oa->targets.point_step +
238 oa->targets.fields[tmpIdx].offset);
243 for (
int iLoop = 0; iLoop < TARGET_MARKER_NUM; iLoop++)
246 rawTargetArray[iLoop].markers[i].header = oa->header;
248 if (useCurrTimeStamp)
250 rawTargetArray[iLoop].markers[i].header.stamp = currTimeStamp;
253 rawTargetArray[iLoop].markers[i].ns =
"rawtargets";
254 rawTargetArray[iLoop].markers[i].id = tmpId + iLoop * numRawTargets;
257 case TARGET_MARKER_ARROW:
259 rawTargetArray[iLoop].markers[i].type = visualization_msgs::Marker::ARROW;
260 rawTargetArray[iLoop].markers[i].scale.x = 0.1;
261 rawTargetArray[iLoop].markers[i].scale.y = 0.2;
263 rawTargetArray[iLoop].markers[i].points.resize(2);
264 rawTargetArray[iLoop].markers[i].points[0].x = pts3d[0];
265 rawTargetArray[iLoop].markers[i].points[0].y = pts3d[1];
266 rawTargetArray[iLoop].markers[i].points[0].z = pts3d[2];
267 float lineOfSight = atan2(pts3d[1], pts3d[0]);
268 rawTargetArray[iLoop].markers[i].points[1].x = pts3d[0] + cos(lineOfSight) * vrad * 0.1;
269 rawTargetArray[iLoop].markers[i].points[1].y = pts3d[1] + sin(lineOfSight) * vrad * 0.1;
270 rawTargetArray[iLoop].markers[i].points[1].z = pts3d[2];
274 case TARGET_MARKER_BALL:
275 rawTargetArray[iLoop].markers[i].type = visualization_msgs::Marker::SPHERE;
276 rawTargetArray[iLoop].markers[i].scale.x =
ballRadius;
277 rawTargetArray[iLoop].markers[i].scale.y =
ballRadius;
278 rawTargetArray[iLoop].markers[i].scale.z =
ballRadius;
281 rawTargetArray[iLoop].markers[i].pose.position.x = pts3d[0];
282 rawTargetArray[iLoop].markers[i].pose.position.y = pts3d[1];
283 rawTargetArray[iLoop].markers[i].pose.position.z = pts3d[2];
284 rawTargetArray[iLoop].markers[i].pose.orientation.x = 0.0;
285 rawTargetArray[iLoop].markers[i].pose.orientation.y = 0.0;
286 rawTargetArray[iLoop].markers[i].pose.orientation.z = 0.0;
287 rawTargetArray[iLoop].markers[i].pose.orientation.w = 1.0;
291 rawTargetArray[iLoop].markers[i].action = visualization_msgs::Marker::ADD;
297 idxRange /= rangeAmpl;
306 unsigned char greyIdx = (
unsigned char)(255.999 * idxRange);
311 float redF, greenF, blueF;
313 greenF =
green / 255.00;
314 blueF =
blue / 255.00;
315 rawTargetArray[iLoop].markers[i].color.a = 0.75;
316 rawTargetArray[iLoop].markers[i].color.r = redF;
317 rawTargetArray[iLoop].markers[i].color.g = greenF;
318 rawTargetArray[iLoop].markers[i].color.b = blueF;
321 rawTargetArray[iLoop].markers[i].color.a = 0.75;
322 rawTargetArray[iLoop].markers[i].color.r =
GLASBEY_LUT[tmpId * 3] / 255.0;
323 rawTargetArray[iLoop].markers[i].color.g =
GLASBEY_LUT[tmpId * 3 + 1] / 255.0;
324 rawTargetArray[iLoop].markers[i].color.b =
GLASBEY_LUT[tmpId * 3 + 2] / 255.0;
326 rawTargetArray[iLoop].markers[i].lifetime =
ros::Duration(0.5);
332 for (
int iLoop = 0; iLoop < TARGET_MARKER_NUM; iLoop++)
344 visualization_msgs::MarkerArray object_boxes;
345 object_boxes.markers.resize(2 * oa->objects.size());
347 visualization_msgs::MarkerArray object_labels;
348 object_labels.markers.resize(1 * oa->objects.size());
351 float vp_dir_deg = 0.0;
353 double angleMainDirDeg = 20;
354 double angleMainDir = angleMainDirDeg / 180.0 * M_PI;
355 double angleMainDirTolDeg = 20.0;
356 double angleMainDirTol = angleMainDirTolDeg / 180.0 * M_PI;
358 std::vector<float> vehiclePredefinedDir;
359 std::vector<float> vehicleAbsoluteSpeed;
360 std::vector<bool> vehicleIsInPredefinedDir;
362 int objNum = oa->objects.size();
364 vehiclePredefinedDir.resize(objNum);
365 vehicleIsInPredefinedDir.resize(objNum);
366 vehicleAbsoluteSpeed.resize(objNum);
368 for (
int iLoop = 0; iLoop < 2; iLoop++)
370 for (
size_t i = 0; i < oa->objects.size(); i++)
372 int colorId = oa->objects[i].id % 256;
374 vp[0] = oa->objects[i].velocity.twist.linear.x;
375 vp[1] = oa->objects[i].velocity.twist.linear.y;
376 vp[2] = oa->objects[i].velocity.twist.linear.z;
377 float vabs = sqrt(vp[0] * vp[0] + vp[1]*vp[1] + vp[2]*vp[2]);
378 vehicleAbsoluteSpeed[i] = vabs;
379 vp_dir = atan2(vp[1], vp[0]);
380 vp_dir_deg = vp_dir / 3.141592 * 180.0;
384 vehiclePredefinedDir[i] = dstAngle;
385 vehicleIsInPredefinedDir[i] = bRet;
387 int idx = i + iLoop * oa->objects.size();
389 object_boxes.markers[idx].header = oa->header;
391 if (useCurrTimeStamp)
393 object_boxes.markers[idx].header.stamp = currTimeStamp;
395 std::string nameSpaceBoxes =
"object_boxes_slow";
398 nameSpaceBoxes =
"object_boxes_fast";
400 object_boxes.markers[idx].ns = nameSpaceBoxes;
401 object_boxes.markers[idx].id = tmpId + iLoop * oa->objects.size();
402 object_boxes.markers[idx].action = visualization_msgs::Marker::ADD;
403 object_boxes.markers[idx].color.a = 0.75;
404 object_boxes.markers[idx].color.r =
GLASBEY_LUT[colorId * 3] / 255.0;
405 object_boxes.markers[idx].color.g =
GLASBEY_LUT[colorId * 3 + 1] / 255.0;
406 object_boxes.markers[idx].color.b =
GLASBEY_LUT[colorId * 3 + 2] / 255.0;
411 object_labels.markers[i].header = oa->header;
412 if (useCurrTimeStamp)
415 object_labels.markers[i].header.stamp = currTimeStamp;
419 object_labels.markers[i].id = tmpId + iLoop * oa->objects.size();
420 object_labels.markers[i].action = visualization_msgs::Marker::ADD;
421 object_labels.markers[i].color.a = 0.75;
422 object_labels.markers[i].color.r =
GLASBEY_LUT[colorId * 3] / 255.0;
423 object_labels.markers[i].color.g =
GLASBEY_LUT[colorId * 3 + 1] / 255.0;
424 object_labels.markers[i].color.b =
GLASBEY_LUT[colorId * 3 + 2] / 255.0;
427 object_labels.markers[i].type = visualization_msgs::Marker::TEXT_VIEW_FACING;
428 object_labels.markers[i].pose = oa->objects[i].object_box_center.pose;
429 object_labels.markers[i].scale.z = 1.0;
434 sprintf(szLabel,
"%5.1lf [m/s]", vabs );
440 std::string object_label_ns =
"???";
443 object_label_ns =
"object_label_fast";
447 object_label_ns =
"object_label_slow";
450 object_labels.markers[i].text = szLabel;
451 object_labels.markers[i].ns = object_label_ns;
453 if (vehicleIsInPredefinedDir[i] ==
false)
455 object_labels.markers[i].scale.z = 0.00;
464 object_boxes.markers[idx].pose = oa->objects[i].object_box_center.pose;
465 object_boxes.markers[idx].scale = oa->objects[i].object_box_size;
470 object_boxes.markers[idx].type = visualization_msgs::Marker::CUBE;
471 object_boxes.markers[idx].pose.position.z += oa->objects[i].object_box_size.z * 0.5;
476 object_boxes.markers[idx].type = visualization_msgs::Marker::ARROW;
484 if (object_boxes.markers[idx].scale.x == 0.0)
486 object_boxes.markers[idx].scale.x = 0.01;
488 if (object_boxes.markers[idx].scale.y == 0.0)
490 object_boxes.markers[idx].scale.y = 0.01;
492 if (object_boxes.markers[idx].scale.z == 0.0)
494 object_boxes.markers[idx].scale.z = 0.01;
497 if (vehicleIsInPredefinedDir[i] ==
false) {
498 object_boxes.markers[idx].scale.x = 0.0;
499 object_boxes.markers[idx].scale.y = 0.0;
500 object_boxes.markers[idx].scale.z = 0.0;
505 if (vehicleIsInPredefinedDir[i] ==
true)
507 float theta = vehiclePredefinedDir[i];
514 float theta2 = 0.5 * theta;
515 object_boxes.markers[idx].pose.orientation.z = sin(theta2);
516 object_boxes.markers[idx].pose.orientation.w = cos(theta2);
528 object_boxes.markers[idx].scale.x = 0.5;
529 object_boxes.markers[idx].scale.y = 0.5;
530 object_boxes.markers[idx].scale.z = 0.5;
537 xTmp = oa->objects[i].object_box_center.pose.position.x;
538 yTmp = oa->objects[i].object_box_center.pose.position.y;
540 double vehLen = oa->objects[i].object_box_size.x;
543 float quaternion[4] = {0};
545 quaternion[0] = oa->objects[i].object_box_center.pose.orientation.x;
546 quaternion[1] = oa->objects[i].object_box_center.pose.orientation.y;
547 quaternion[2] = oa->objects[i].object_box_center.pose.orientation.z;
548 quaternion[3] = oa->objects[i].object_box_center.pose.orientation.w;
555 float theta2 = atan2(quaternion[2], quaternion[3]);
556 float theta = 2.0f * theta2;
557 if (vehicleIsInPredefinedDir[i] ==
true)
559 theta = vehiclePredefinedDir[i];
562 float cosVal = cos(theta);
563 float sinVal = sin(theta);
564 xTmp += cosVal * vehLen * 0.5;
565 yTmp += sinVal * vehLen * 0.5;
566 object_boxes.markers[idx].pose.position.x = xTmp;
567 object_boxes.markers[idx].pose.position.y = yTmp;
568 object_boxes.markers[idx].pose.position.z = 0.0;
572 object_boxes.markers[idx].pose.orientation.x = 0.0;
573 object_boxes.markers[idx].pose.orientation.y = 0.0;
574 object_boxes.markers[idx].pose.orientation.z = 0.0;
575 object_boxes.markers[idx].pose.orientation.w = 0.0;
577 object_boxes.markers[idx].points.resize(2);
578 object_boxes.markers[idx].points[0].x = 0.0;
579 object_boxes.markers[idx].points[0].y = 0.0;
580 object_boxes.markers[idx].points[0].z = 0.0;
582 float absSpeed = 0.0;
583 for (
int j = 0; j < 3; j++)
585 float speedPartial = 0.0;
588 case 0: speedPartial = oa->objects[i].velocity.twist.linear.x;
break;
589 case 1: speedPartial = oa->objects[i].velocity.twist.linear.y;
break;
590 case 2: speedPartial = oa->objects[i].velocity.twist.linear.z;
break;
592 absSpeed += speedPartial * speedPartial;
594 absSpeed = sqrt(absSpeed);
602 if (vehicleIsInPredefinedDir[i] ==
false) {
606 object_boxes.markers[idx].points[1].x = 0.0 + lengthOfArrow * cosVal;
607 object_boxes.markers[idx].points[1].y = 0.0 + lengthOfArrow * sinVal;
608 object_boxes.markers[idx].points[1].z = 0.0;
624 int main(
int argc,
char **argv)
627 ROS_INFO(
"radar_object_marker, compiled at [%s] [%s]", __DATE__, __TIME__);
628 RadarObjectMarkerCfg *cfgPtr = &boost::serialization::singleton<RadarObjectMarkerCfg>::get_mutable_instance();
629 ros::init(argc, argv,
"radar_object_marker");
634 double minAmpl = 10.0;
635 double maxAmpl = 90.0;
637 paramRes = nhPriv.
getParam(
"rawtarget_palette_name", heatMap);
638 paramRes = nhPriv.
getParam(
"rawtarget_palette_min_ampl", minAmpl);
639 paramRes = nhPriv.
getParam(
"rawtarget_palette_max_ampl", maxAmpl);
653 std::string heatMapFileName = path +
"/config/" + cfgPtr->
getPaletteName();
664 ROS_INFO(
"Subscribing to radar and pulishing to radar_markers");
667 pub = nh.
advertise<visualization_msgs::MarkerArray>(
"radar_markers", 1);