Skip to content

Commit 45280d0

Browse files
feat(autonomous_emergency_braking): cherry pick latest aeb (#1604)
* refactor(autoware_autonomous_emergency_braking): rename info_marker_publisher to virtual_wall_publisher (autowarefoundation#9078) Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * fix(autonomous_emergency_braking): fix no backward imu path and wrong back distance usage (autowarefoundation#9141) * fix no backward imu path and wrong back distance usage Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * use the motion utils isDrivingForward function Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> --------- Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> --------- Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> Co-authored-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp>
1 parent a8719a9 commit 45280d0

File tree

2 files changed

+13
-10
lines changed
  • control/autoware_autonomous_emergency_braking

2 files changed

+13
-10
lines changed

control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -341,7 +341,7 @@ class AEB : public rclcpp::Node
341341
// publisher
342342
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_obstacle_pointcloud_;
343343
rclcpp::Publisher<MarkerArray>::SharedPtr debug_marker_publisher_;
344-
rclcpp::Publisher<MarkerArray>::SharedPtr info_marker_publisher_;
344+
rclcpp::Publisher<MarkerArray>::SharedPtr virtual_wall_publisher_;
345345
rclcpp::Publisher<autoware::universe_utils::ProcessingTimeDetail>::SharedPtr
346346
debug_processing_time_detail_pub_;
347347
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr debug_rss_distance_publisher_;

control/autoware_autonomous_emergency_braking/src/node.cpp

+12-9
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include <autoware/autonomous_emergency_braking/node.hpp>
1616
#include <autoware/autonomous_emergency_braking/utils.hpp>
1717
#include <autoware/motion_utils/marker/marker_helper.hpp>
18+
#include <autoware/motion_utils/trajectory/trajectory.hpp>
1819
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
1920
#include <autoware/universe_utils/geometry/boost_polygon_utils.hpp>
2021
#include <autoware/universe_utils/geometry/geometry.hpp>
@@ -138,7 +139,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options)
138139
pub_obstacle_pointcloud_ =
139140
this->create_publisher<sensor_msgs::msg::PointCloud2>("~/debug/obstacle_pointcloud", 1);
140141
debug_marker_publisher_ = this->create_publisher<MarkerArray>("~/debug/markers", 1);
141-
info_marker_publisher_ = this->create_publisher<MarkerArray>("~/info/markers", 1);
142+
virtual_wall_publisher_ = this->create_publisher<MarkerArray>("~/virtual_wall", 1);
142143
debug_rss_distance_publisher_ =
143144
this->create_publisher<tier4_debug_msgs::msg::Float32Stamped>("~/debug/rss_distance", 1);
144145
}
@@ -398,7 +399,7 @@ bool AEB::fetchLatestData()
398399
void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
399400
{
400401
MarkerArray debug_markers;
401-
MarkerArray info_markers;
402+
MarkerArray virtual_wall_marker;
402403
checkCollision(debug_markers);
403404

404405
if (!collision_data_keeper_.checkCollisionExpired()) {
@@ -414,7 +415,7 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
414415
addCollisionMarker(data.value(), debug_markers);
415416
}
416417
}
417-
addVirtualStopWallMarker(info_markers);
418+
addVirtualStopWallMarker(virtual_wall_marker);
418419
} else {
419420
const std::string error_msg = "[AEB]: No Collision";
420421
const auto diag_level = DiagnosticStatus::OK;
@@ -423,7 +424,7 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
423424

424425
// publish debug markers
425426
debug_marker_publisher_->publish(debug_markers);
426-
info_marker_publisher_->publish(info_markers);
427+
virtual_wall_publisher_->publish(virtual_wall_marker);
427428
}
428429

429430
bool AEB::checkCollision(MarkerArray & debug_markers)
@@ -642,7 +643,7 @@ Path AEB::generateEgoPath(const double curr_v, const double curr_w)
642643
ini_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(curr_yaw);
643644
path.push_back(ini_pose);
644645
const double & dt = imu_prediction_time_interval_;
645-
const double distance_between_points = curr_v * dt;
646+
const double distance_between_points = std::abs(curr_v) * dt;
646647
constexpr double minimum_distance_between_points{1e-2};
647648
// if current velocity is too small, assume it stops at the same point
648649
// if distance between points is too small, arc length calculation is unreliable, so we skip
@@ -887,7 +888,11 @@ void AEB::getClosestObjectsOnPath(
887888
if (ego_path.size() < 2 || points_belonging_to_cluster_hulls->empty()) {
888889
return;
889890
}
890-
891+
const auto ego_is_driving_forward_opt = autoware::motion_utils::isDrivingForward(ego_path);
892+
if (!ego_is_driving_forward_opt.has_value()) {
893+
return;
894+
}
895+
const bool ego_is_driving_forward = ego_is_driving_forward_opt.value();
891896
// select points inside the ego footprint path
892897
const auto current_p = [&]() {
893898
const auto & first_point_of_path = ego_path.front();
@@ -916,11 +921,9 @@ void AEB::getClosestObjectsOnPath(
916921

917922
// If the object is behind the ego, we need to use the backward long offset. The distance should
918923
// be a positive number in any case
919-
const bool is_object_in_front_of_ego = obj_arc_length > 0.0;
920-
const double dist_ego_to_object = (is_object_in_front_of_ego)
924+
const double dist_ego_to_object = (ego_is_driving_forward)
921925
? obj_arc_length - vehicle_info_.max_longitudinal_offset_m
922926
: obj_arc_length + vehicle_info_.min_longitudinal_offset_m;
923-
924927
ObjectData obj;
925928
obj.stamp = stamp;
926929
obj.position = obj_position;

0 commit comments

Comments
 (0)