Skip to content

Commit d3da155

Browse files
soblindanielsanchezaran
authored andcommitted
fix(AEB): check empty path at low speed (autowarefoundation#6346)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent c0035db commit d3da155

File tree

3 files changed

+33
-27
lines changed

3 files changed

+33
-27
lines changed

control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@
4141

4242
#include <memory>
4343
#include <mutex>
44+
#include <optional>
4445
#include <string>
4546
#include <vector>
4647

@@ -140,10 +141,9 @@ class AEB : public rclcpp::Node
140141
bool hasCollision(
141142
const double current_v, const Path & ego_path, const std::vector<ObjectData> & objects);
142143

143-
void generateEgoPath(
144-
const double curr_v, const double curr_w, Path & path, std::vector<Polygon2d> & polygons);
145-
void generateEgoPath(
146-
const Trajectory & predicted_traj, Path & path, std::vector<Polygon2d> & polygons);
144+
Path generateEgoPath(const double curr_v, const double curr_w, std::vector<Polygon2d> & polygons);
145+
std::optional<Path> generateEgoPath(
146+
const Trajectory & predicted_traj, std::vector<Polygon2d> & polygons);
147147
void createObjectData(
148148
const Path & ego_path, const std::vector<Polygon2d> & ego_polys, const rclcpp::Time & stamp,
149149
std::vector<ObjectData> & objects);

control/autonomous_emergency_braking/package.xml

+5-2
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,11 @@
33
<package format="3">
44
<name>autonomous_emergency_braking</name>
55
<version>0.1.0</version>
6-
<description>Autonomous Emergency Braking package as a ROS2 node</description>
7-
<maintainer email="yutaka.shimizu@tier4.jp">yutaka</maintainer>
6+
<description>Autonomous Emergency Braking package as a ROS 2 node</description>
7+
<maintainer email="takamasa.horibe@tier4.jp">Takamasa Horibe</maintainer>
8+
<maintainer email="tomoya.kimura@tier4.jp">Tomoya Kimura</maintainer>
9+
<maintainer email="mamoru.sobue@tier4.jp">Mamoru Sobue</maintainer>
10+
811
<license>Apache License 2.0</license>
912

1013
<buildtool_depend>ament_cmake</buildtool_depend>

control/autonomous_emergency_braking/src/node.cpp

+24-21
Original file line numberDiff line numberDiff line change
@@ -308,16 +308,14 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
308308
// step3. create ego path based on sensor data
309309
bool has_collision_ego = false;
310310
if (use_imu_path_) {
311-
Path ego_path;
312311
std::vector<Polygon2d> ego_polys;
313312
const double current_w = angular_velocity_ptr_->z;
314313
constexpr double color_r = 0.0 / 256.0;
315314
constexpr double color_g = 148.0 / 256.0;
316315
constexpr double color_b = 205.0 / 256.0;
317316
constexpr double color_a = 0.999;
318317
const auto current_time = get_clock()->now();
319-
generateEgoPath(current_v, current_w, ego_path, ego_polys);
320-
318+
const auto ego_path = generateEgoPath(current_v, current_w, ego_polys);
321319
std::vector<ObjectData> objects;
322320
createObjectData(ego_path, ego_polys, current_time, objects);
323321
has_collision_ego = hasCollision(current_v, ego_path, objects);
@@ -331,23 +329,25 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
331329
// step4. transform predicted trajectory from control module
332330
bool has_collision_predicted = false;
333331
if (use_predicted_trajectory_) {
334-
Path predicted_path;
335332
std::vector<Polygon2d> predicted_polys;
336333
const auto predicted_traj_ptr = predicted_traj_ptr_;
337334
constexpr double color_r = 0.0;
338335
constexpr double color_g = 100.0 / 256.0;
339336
constexpr double color_b = 0.0;
340337
constexpr double color_a = 0.999;
341338
const auto current_time = predicted_traj_ptr->header.stamp;
342-
generateEgoPath(*predicted_traj_ptr, predicted_path, predicted_polys);
343-
std::vector<ObjectData> objects;
344-
createObjectData(predicted_path, predicted_polys, current_time, objects);
345-
has_collision_predicted = hasCollision(current_v, predicted_path, objects);
346-
347-
std::string ns = "predicted";
348-
addMarker(
349-
current_time, predicted_path, predicted_polys, objects, color_r, color_g, color_b, color_a,
350-
ns, debug_markers);
339+
const auto predicted_path_opt = generateEgoPath(*predicted_traj_ptr, predicted_polys);
340+
if (predicted_path_opt) {
341+
const auto & predicted_path = predicted_path_opt.value();
342+
std::vector<ObjectData> objects;
343+
createObjectData(predicted_path, predicted_polys, current_time, objects);
344+
has_collision_predicted = hasCollision(current_v, predicted_path, objects);
345+
346+
std::string ns = "predicted";
347+
addMarker(
348+
current_time, predicted_path, predicted_polys, objects, color_r, color_g, color_b, color_a,
349+
ns, debug_markers);
350+
}
351351
}
352352
std::cerr << "Has collision! \n";
353353
return has_collision_ego || has_collision_predicted;
@@ -383,9 +383,10 @@ bool AEB::hasCollision(
383383
return false;
384384
}
385385

386-
void AEB::generateEgoPath(
387-
const double curr_v, const double curr_w, Path & path, std::vector<Polygon2d> & polygons)
386+
Path AEB::generateEgoPath(
387+
const double curr_v, const double curr_w, std::vector<Polygon2d> & polygons)
388388
{
389+
Path path;
389390
double curr_x = 0.0;
390391
double curr_y = 0.0;
391392
double curr_yaw = 0.0;
@@ -396,7 +397,7 @@ void AEB::generateEgoPath(
396397

397398
if (curr_v < 0.1) {
398399
// if current velocity is too small, assume it stops at the same point
399-
return;
400+
return path;
400401
}
401402

402403
constexpr double epsilon = 1e-6;
@@ -434,14 +435,14 @@ void AEB::generateEgoPath(
434435
for (size_t i = 0; i < path.size() - 1; ++i) {
435436
polygons.at(i) = createPolygon(path.at(i), path.at(i + 1), vehicle_info_, expand_width_);
436437
}
438+
return path;
437439
}
438440

439-
void AEB::generateEgoPath(
440-
const Trajectory & predicted_traj, Path & path,
441-
std::vector<tier4_autoware_utils::Polygon2d> & polygons)
441+
std::optional<Path> AEB::generateEgoPath(
442+
const Trajectory & predicted_traj, std::vector<tier4_autoware_utils::Polygon2d> & polygons)
442443
{
443444
if (predicted_traj.points.empty()) {
444-
return;
445+
return std::nullopt;
445446
}
446447

447448
geometry_msgs::msg::TransformStamped transform_stamped{};
@@ -451,10 +452,11 @@ void AEB::generateEgoPath(
451452
rclcpp::Duration::from_seconds(0.5));
452453
} catch (tf2::TransformException & ex) {
453454
RCLCPP_ERROR_STREAM(get_logger(), "[AEB] Failed to look up transform from base_link to map");
454-
return;
455+
return std::nullopt;
455456
}
456457

457458
// create path
459+
Path path;
458460
path.resize(predicted_traj.points.size());
459461
for (size_t i = 0; i < predicted_traj.points.size(); ++i) {
460462
geometry_msgs::msg::Pose map_pose;
@@ -470,6 +472,7 @@ void AEB::generateEgoPath(
470472
for (size_t i = 0; i < path.size() - 1; ++i) {
471473
polygons.at(i) = createPolygon(path.at(i), path.at(i + 1), vehicle_info_, expand_width_);
472474
}
475+
return path;
473476
}
474477

475478
void AEB::createObjectData(

0 commit comments

Comments
 (0)