@@ -452,14 +452,7 @@ BehaviorModuleOutput StartPlannerModule::plan()
452
452
453
453
setDrivableAreaInfo (output);
454
454
455
- const uint16_t steering_factor_direction = std::invoke ([&output]() {
456
- if (output.turn_signal_info .turn_signal .command == TurnIndicatorsCommand::ENABLE_LEFT) {
457
- return SteeringFactor::LEFT;
458
- } else if (output.turn_signal_info .turn_signal .command == TurnIndicatorsCommand::ENABLE_RIGHT) {
459
- return SteeringFactor::RIGHT;
460
- }
461
- return SteeringFactor::STRAIGHT;
462
- });
455
+ const auto steering_factor_direction = getSteeringFactorDirection (output);
463
456
464
457
if (status_.driving_forward ) {
465
458
const double start_distance = motion_utils::calcSignedArcLength (
@@ -473,15 +466,16 @@ BehaviorModuleOutput StartPlannerModule::plan()
473
466
{status_.pull_out_path .start_pose , status_.pull_out_path .end_pose },
474
467
{start_distance, finish_distance}, PlanningBehavior::START_PLANNER, steering_factor_direction,
475
468
SteeringFactor::TURNING, " " );
476
- } else {
477
- const double distance = motion_utils::calcSignedArcLength (
478
- path.points , planner_data_->self_odometry ->pose .pose .position ,
479
- status_.pull_out_path .start_pose .position );
480
- updateRTCStatus (0.0 , distance);
481
- steering_factor_interface_ptr_->updateSteeringFactor (
482
- {status_.pull_out_path .start_pose , status_.pull_out_path .end_pose }, {0.0 , distance},
483
- PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, " " );
469
+ setDebugData ();
470
+ return output;
484
471
}
472
+ const double distance = motion_utils::calcSignedArcLength (
473
+ path.points , planner_data_->self_odometry ->pose .pose .position ,
474
+ status_.pull_out_path .start_pose .position );
475
+ updateRTCStatus (0.0 , distance);
476
+ steering_factor_interface_ptr_->updateSteeringFactor (
477
+ {status_.pull_out_path .start_pose , status_.pull_out_path .end_pose }, {0.0 , distance},
478
+ PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, " " );
485
479
486
480
setDebugData ();
487
481
@@ -562,14 +556,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval()
562
556
563
557
setDrivableAreaInfo (output);
564
558
565
- const uint16_t steering_factor_direction = std::invoke ([&output]() {
566
- if (output.turn_signal_info .turn_signal .command == TurnIndicatorsCommand::ENABLE_LEFT) {
567
- return SteeringFactor::LEFT;
568
- } else if (output.turn_signal_info .turn_signal .command == TurnIndicatorsCommand::ENABLE_RIGHT) {
569
- return SteeringFactor::RIGHT;
570
- }
571
- return SteeringFactor::STRAIGHT;
572
- });
559
+ const auto steering_factor_direction = getSteeringFactorDirection (output);
573
560
574
561
if (status_.driving_forward ) {
575
562
const double start_distance = motion_utils::calcSignedArcLength (
@@ -583,15 +570,17 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval()
583
570
{status_.pull_out_path .start_pose , status_.pull_out_path .end_pose },
584
571
{start_distance, finish_distance}, PlanningBehavior::START_PLANNER, steering_factor_direction,
585
572
SteeringFactor::APPROACHING, " " );
586
- } else {
587
- const double distance = motion_utils::calcSignedArcLength (
588
- stop_path.points , planner_data_->self_odometry ->pose .pose .position ,
589
- status_.pull_out_path .start_pose .position );
590
- updateRTCStatus (0.0 , distance);
591
- steering_factor_interface_ptr_->updateSteeringFactor (
592
- {status_.pull_out_path .start_pose , status_.pull_out_path .end_pose }, {0.0 , distance},
593
- PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::APPROACHING, " " );
573
+ setDebugData ();
574
+
575
+ return output;
594
576
}
577
+ const double distance = motion_utils::calcSignedArcLength (
578
+ stop_path.points , planner_data_->self_odometry ->pose .pose .position ,
579
+ status_.pull_out_path .start_pose .position );
580
+ updateRTCStatus (0.0 , distance);
581
+ steering_factor_interface_ptr_->updateSteeringFactor (
582
+ {status_.pull_out_path .start_pose , status_.pull_out_path .end_pose }, {0.0 , distance},
583
+ PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::APPROACHING, " " );
595
584
596
585
setDebugData ();
597
586
@@ -652,16 +641,20 @@ PriorityOrder StartPlannerModule::determinePriorityOrder(
652
641
order_priority.emplace_back (i, planner);
653
642
}
654
643
}
655
- } else if (search_priority == " short_back_distance" ) {
644
+ return order_priority;
645
+ }
646
+
647
+ if (search_priority == " short_back_distance" ) {
656
648
for (size_t i = 0 ; i < start_pose_candidates_num; i++) {
657
649
for (const auto & planner : start_planners_) {
658
650
order_priority.emplace_back (i, planner);
659
651
}
660
652
}
661
- } else {
662
- RCLCPP_ERROR (getLogger (), " Invalid search_priority: %s" , search_priority.c_str ());
663
- throw std::domain_error (" [start_planner] invalid search_priority" );
653
+ return order_priority;
664
654
}
655
+
656
+ RCLCPP_ERROR (getLogger (), " Invalid search_priority: %s" , search_priority.c_str ());
657
+ throw std::domain_error (" [start_planner] invalid search_priority" );
665
658
return order_priority;
666
659
}
667
660
@@ -1093,12 +1086,7 @@ bool StartPlannerModule::isStuck()
1093
1086
return false ;
1094
1087
}
1095
1088
1096
- if (status_.planner_type == PlannerType::STOP) {
1097
- return true ;
1098
- }
1099
-
1100
- // not found safe path
1101
- if (!status_.found_pull_out_path ) {
1089
+ if (status_.planner_type == PlannerType::STOP || !status_.found_pull_out_path ) {
1102
1090
return true ;
1103
1091
}
1104
1092
@@ -1191,30 +1179,26 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() const
1191
1179
return false ;
1192
1180
});
1193
1181
1194
- if (is_near_intersection) {
1195
- // offset required end pose with ration to activate turn signal for intersection
1196
- turn_signal.required_end_point = std::invoke ([&]() {
1197
- const double length_start_to_end =
1198
- motion_utils::calcSignedArcLength (path.points , start_pose.position , end_pose.position );
1199
- const auto ratio = std::clamp (
1200
- parameters_->length_ratio_for_turn_signal_deactivation_near_intersection , 0.0 , 1.0 );
1201
-
1202
- const double required_end_length = length_start_to_end * ratio;
1203
- double accumulated_length = 0.0 ;
1204
- const size_t start_idx = motion_utils::findNearestIndex (path.points , start_pose.position );
1205
- for (size_t i = start_idx; i < path.points .size () - 1 ; ++i) {
1206
- accumulated_length +=
1207
- tier4_autoware_utils::calcDistance2d (path.points .at (i), path.points .at (i + 1 ));
1208
- if (accumulated_length > required_end_length) {
1209
- return path.points .at (i).point .pose ;
1210
- }
1182
+ turn_signal.required_end_point = std::invoke ([&]() {
1183
+ if (is_near_intersection) return end_pose;
1184
+ const double length_start_to_end =
1185
+ motion_utils::calcSignedArcLength (path.points , start_pose.position , end_pose.position );
1186
+ const auto ratio = std::clamp (
1187
+ parameters_->length_ratio_for_turn_signal_deactivation_near_intersection , 0.0 , 1.0 );
1188
+
1189
+ const double required_end_length = length_start_to_end * ratio;
1190
+ double accumulated_length = 0.0 ;
1191
+ const size_t start_idx = motion_utils::findNearestIndex (path.points , start_pose.position );
1192
+ for (size_t i = start_idx; i < path.points .size () - 1 ; ++i) {
1193
+ accumulated_length +=
1194
+ tier4_autoware_utils::calcDistance2d (path.points .at (i), path.points .at (i + 1 ));
1195
+ if (accumulated_length > required_end_length) {
1196
+ return path.points .at (i).point .pose ;
1211
1197
}
1212
- // not found required end point
1213
- return end_pose;
1214
- });
1215
- } else {
1216
- turn_signal.required_end_point = end_pose;
1217
- }
1198
+ }
1199
+ // not found required end point
1200
+ return end_pose;
1201
+ });
1218
1202
1219
1203
return turn_signal;
1220
1204
}
@@ -1383,22 +1367,27 @@ bool StartPlannerModule::planFreespacePath()
1383
1367
1384
1368
void StartPlannerModule::setDrivableAreaInfo (BehaviorModuleOutput & output) const
1385
1369
{
1386
- if (status_.planner_type == PlannerType::FREESPACE) {
1387
- const double drivable_area_margin = planner_data_->parameters .vehicle_width ;
1388
- output.drivable_area_info .drivable_margin =
1389
- planner_data_->parameters .vehicle_width / 2.0 + drivable_area_margin;
1390
- } else {
1391
- const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes (
1392
- output.path , generateDrivableLanes (output.path ),
1393
- planner_data_->drivable_area_expansion_parameters );
1394
-
1395
- DrivableAreaInfo current_drivable_area_info;
1396
- current_drivable_area_info.drivable_lanes = target_drivable_lanes;
1397
- output.drivable_area_info =
1398
- status_.driving_forward
1399
- ? utils::combineDrivableAreaInfo (
1400
- current_drivable_area_info, getPreviousModuleOutput ().drivable_area_info )
1401
- : current_drivable_area_info;
1370
+ switch (status_.planner_type ) {
1371
+ case PlannerType::FREESPACE: {
1372
+ const double drivable_area_margin = planner_data_->parameters .vehicle_width ;
1373
+ output.drivable_area_info .drivable_margin =
1374
+ planner_data_->parameters .vehicle_width / 2.0 + drivable_area_margin;
1375
+ break ;
1376
+ }
1377
+ default : {
1378
+ const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes (
1379
+ output.path , generateDrivableLanes (output.path ),
1380
+ planner_data_->drivable_area_expansion_parameters );
1381
+
1382
+ DrivableAreaInfo current_drivable_area_info;
1383
+ current_drivable_area_info.drivable_lanes = target_drivable_lanes;
1384
+ output.drivable_area_info =
1385
+ status_.driving_forward
1386
+ ? utils::combineDrivableAreaInfo (
1387
+ current_drivable_area_info, getPreviousModuleOutput ().drivable_area_info )
1388
+ : current_drivable_area_info;
1389
+ break ;
1390
+ }
1402
1391
}
1403
1392
}
1404
1393
0 commit comments