@@ -308,16 +308,14 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
308
308
// step3. create ego path based on sensor data
309
309
bool has_collision_ego = false ;
310
310
if (use_imu_path_) {
311
- Path ego_path;
312
311
std::vector<Polygon2d> ego_polys;
313
312
const double current_w = angular_velocity_ptr_->z ;
314
313
constexpr double color_r = 0.0 / 256.0 ;
315
314
constexpr double color_g = 148.0 / 256.0 ;
316
315
constexpr double color_b = 205.0 / 256.0 ;
317
316
constexpr double color_a = 0.999 ;
318
317
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);
321
319
std::vector<ObjectData> objects;
322
320
createObjectData (ego_path, ego_polys, current_time, objects);
323
321
has_collision_ego = hasCollision (current_v, ego_path, objects);
@@ -331,23 +329,25 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
331
329
// step4. transform predicted trajectory from control module
332
330
bool has_collision_predicted = false ;
333
331
if (use_predicted_trajectory_) {
334
- Path predicted_path;
335
332
std::vector<Polygon2d> predicted_polys;
336
333
const auto predicted_traj_ptr = predicted_traj_ptr_;
337
334
constexpr double color_r = 0.0 ;
338
335
constexpr double color_g = 100.0 / 256.0 ;
339
336
constexpr double color_b = 0.0 ;
340
337
constexpr double color_a = 0.999 ;
341
338
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
+ }
351
351
}
352
352
std::cerr << " Has collision! \n " ;
353
353
return has_collision_ego || has_collision_predicted;
@@ -383,9 +383,10 @@ bool AEB::hasCollision(
383
383
return false ;
384
384
}
385
385
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)
388
388
{
389
+ Path path;
389
390
double curr_x = 0.0 ;
390
391
double curr_y = 0.0 ;
391
392
double curr_yaw = 0.0 ;
@@ -396,7 +397,7 @@ void AEB::generateEgoPath(
396
397
397
398
if (curr_v < 0.1 ) {
398
399
// if current velocity is too small, assume it stops at the same point
399
- return ;
400
+ return path ;
400
401
}
401
402
402
403
constexpr double epsilon = 1e-6 ;
@@ -434,14 +435,14 @@ void AEB::generateEgoPath(
434
435
for (size_t i = 0 ; i < path.size () - 1 ; ++i) {
435
436
polygons.at (i) = createPolygon (path.at (i), path.at (i + 1 ), vehicle_info_, expand_width_);
436
437
}
438
+ return path;
437
439
}
438
440
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)
442
443
{
443
444
if (predicted_traj.points .empty ()) {
444
- return ;
445
+ return std::nullopt ;
445
446
}
446
447
447
448
geometry_msgs::msg::TransformStamped transform_stamped{};
@@ -451,10 +452,11 @@ void AEB::generateEgoPath(
451
452
rclcpp::Duration::from_seconds (0.5 ));
452
453
} catch (tf2::TransformException & ex) {
453
454
RCLCPP_ERROR_STREAM (get_logger (), " [AEB] Failed to look up transform from base_link to map" );
454
- return ;
455
+ return std::nullopt ;
455
456
}
456
457
457
458
// create path
459
+ Path path;
458
460
path.resize (predicted_traj.points .size ());
459
461
for (size_t i = 0 ; i < predicted_traj.points .size (); ++i) {
460
462
geometry_msgs::msg::Pose map_pose;
@@ -470,6 +472,7 @@ void AEB::generateEgoPath(
470
472
for (size_t i = 0 ; i < path.size () - 1 ; ++i) {
471
473
polygons.at (i) = createPolygon (path.at (i), path.at (i + 1 ), vehicle_info_, expand_width_);
472
474
}
475
+ return path;
473
476
}
474
477
475
478
void AEB::createObjectData (
0 commit comments