@@ -364,8 +364,9 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
364
364
}
365
365
366
366
// step2. create velocity data check if the vehicle stops or not
367
+ constexpr double min_moving_velocity_th{0.1 };
367
368
const double current_v = current_velocity_ptr_->longitudinal_velocity ;
368
- if (current_v < 0.1 ) {
369
+ if (std::abs ( current_v) < min_moving_velocity_th ) {
369
370
return false ;
370
371
}
371
372
@@ -463,7 +464,8 @@ bool AEB::hasCollision(const double current_v, const ObjectData & closest_object
463
464
{
464
465
const double & obj_v = closest_object.velocity ;
465
466
const double & t = t_response_;
466
- const double rss_dist = current_v * t + (current_v * current_v) / (2 * std::fabs (a_ego_min_)) -
467
+ const double rss_dist = std::abs (current_v) * t +
468
+ (current_v * current_v) / (2 * std::fabs (a_ego_min_)) -
467
469
obj_v * obj_v / (2 * std::fabs (a_obj_min_)) + longitudinal_offset_;
468
470
if (closest_object.distance_to_object < rss_dist) {
469
471
// collision happens
@@ -487,7 +489,7 @@ Path AEB::generateEgoPath(const double curr_v, const double curr_w)
487
489
ini_pose.orientation = tier4_autoware_utils::createQuaternionFromYaw (curr_yaw);
488
490
path.push_back (ini_pose);
489
491
490
- if (curr_v < 0.1 ) {
492
+ if (std::abs ( curr_v) < 0.1 ) {
491
493
// if current velocity is too small, assume it stops at the same point
492
494
return path;
493
495
}
@@ -610,22 +612,30 @@ void AEB::createObjectDataUsingPointCloudClusters(
610
612
}
611
613
612
614
// select points inside the ego footprint path
613
- const auto current_p = tier4_autoware_utils::createPoint (
614
- ego_path[0 ].position .x , ego_path[0 ].position .y , ego_path[0 ].position .z );
615
+ const auto current_p = [&]() {
616
+ const auto & first_point_of_path = ego_path.front ();
617
+ const auto & p = first_point_of_path.position ;
618
+ return tier4_autoware_utils::createPoint (p.x , p.y , p.z );
619
+ }();
615
620
616
621
for (const auto & p : *points_belonging_to_cluster_hulls) {
617
622
const auto obj_position = tier4_autoware_utils::createPoint (p.x , p.y , p.z );
618
- const double dist_ego_to_object =
619
- motion_utils::calcSignedArcLength (ego_path, current_p, obj_position) -
620
- vehicle_info_.max_longitudinal_offset_m ;
621
- // objects behind ego are ignored
622
- if (dist_ego_to_object < 0.0 ) continue ;
623
+ const double obj_arc_length =
624
+ motion_utils::calcSignedArcLength (ego_path, current_p, obj_position);
625
+ if (std::isnan (obj_arc_length)) continue ;
626
+
627
+ // If the object is behind the ego, we need to use the backward long offset. The distance should
628
+ // be a positive number in any case
629
+ const bool is_object_in_front_of_ego = obj_arc_length > 0.0 ;
630
+ const double dist_ego_to_object = (is_object_in_front_of_ego)
631
+ ? obj_arc_length - vehicle_info_.max_longitudinal_offset_m
632
+ : obj_arc_length + vehicle_info_.min_longitudinal_offset_m ;
623
633
624
634
ObjectData obj;
625
635
obj.stamp = stamp;
626
636
obj.position = obj_position;
627
637
obj.velocity = 0.0 ;
628
- obj.distance_to_object = dist_ego_to_object;
638
+ obj.distance_to_object = std::abs ( dist_ego_to_object) ;
629
639
630
640
const Point2d obj_point (p.x , p.y );
631
641
for (const auto & ego_poly : ego_polys) {
@@ -721,7 +731,8 @@ void AEB::addMarker(
721
731
closest_object_velocity_marker_array.text =
722
732
" Object velocity: " + std::to_string (obj.velocity ) + " [m/s]\n " ;
723
733
closest_object_velocity_marker_array.text +=
724
- " Object relative velocity to ego: " + std::to_string (obj.velocity - ego_velocity) + " [m/s]" ;
734
+ " Object relative velocity to ego: " + std::to_string (obj.velocity - std::abs (ego_velocity)) +
735
+ " [m/s]" ;
725
736
debug_markers.markers .push_back (closest_object_velocity_marker_array);
726
737
}
727
738
}
0 commit comments