@@ -350,7 +350,8 @@ void StartPlannerModuleManager::updateModuleParams(
350
350
updateParam<double >(
351
351
parameters, ns + " length_ratio_for_turn_signal_deactivation_near_intersection" ,
352
352
p->length_ratio_for_turn_signal_deactivation_near_intersection );
353
-
353
+ updateParam<std::vector<double >>(
354
+ parameters, ns + " collision_check_margins" , p->collision_check_margins );
354
355
updateParam<double >(
355
356
parameters, ns + " collision_check_margin_from_front_object" ,
356
357
p->collision_check_margin_from_front_object );
@@ -380,6 +381,16 @@ void StartPlannerModuleManager::updateModuleParams(
380
381
parameters, ns + " pull_out_max_steer_angle" ,
381
382
p->parallel_parking_parameters .pull_out_max_steer_angle );
382
383
updateParam<bool >(parameters, ns + " enable_back" , p->enable_back );
384
+ updateParam<double >(parameters, ns + " backward_velocity" , p->backward_velocity );
385
+ updateParam<double >(
386
+ parameters, ns + " geometric_pull_out_velocity" ,
387
+ p->parallel_parking_parameters .pull_out_velocity );
388
+ updateParam<double >(
389
+ parameters, ns + " geometric_collision_check_distance_from_end" ,
390
+ p->geometric_collision_check_distance_from_end );
391
+ updateParam<bool >(
392
+ parameters, ns + " check_shift_path_lane_departure" , p->check_shift_path_lane_departure );
393
+ updateParam<std::string>(parameters, ns + " search_priority" , p->search_priority );
383
394
updateParam<double >(parameters, ns + " max_back_distance" , p->max_back_distance );
384
395
updateParam<double >(
385
396
parameters, ns + " backward_search_resolution" , p->backward_search_resolution );
@@ -392,6 +403,8 @@ void StartPlannerModuleManager::updateModuleParams(
392
403
const std::string ns = " start_planner.freespace_planner." ;
393
404
394
405
updateParam<bool >(parameters, ns + " enable_freespace_planner" , p->enable_freespace_planner );
406
+ updateParam<std::string>(
407
+ parameters, ns + " freespace_planner_algorithm" , p->freespace_planner_algorithm );
395
408
updateParam<double >(
396
409
parameters, ns + " end_pose_search_start_distance" , p->end_pose_search_start_distance );
397
410
updateParam<double >(
@@ -410,6 +423,11 @@ void StartPlannerModuleManager::updateModuleParams(
410
423
updateParam<int >(
411
424
parameters, ns + " turning_radius_size" ,
412
425
p->freespace_planner_common_parameters .turning_radius_size );
426
+ p->freespace_planner_common_parameters .maximum_turning_radius = std::max (
427
+ p->freespace_planner_common_parameters .maximum_turning_radius ,
428
+ p->freespace_planner_common_parameters .minimum_turning_radius );
429
+ p->freespace_planner_common_parameters .turning_radius_size =
430
+ std::max (p->freespace_planner_common_parameters .turning_radius_size , 1 );
413
431
}
414
432
{
415
433
const std::string ns = " start_planner.freespace_planner.search_configs." ;
@@ -442,6 +460,10 @@ void StartPlannerModuleManager::updateModuleParams(
442
460
const std::string ns = " start_planner.freespace_planner.astar." ;
443
461
444
462
updateParam<bool >(parameters, ns + " use_back" , p->astar_parameters .use_back );
463
+ updateParam<bool >(
464
+ parameters, ns + " only_behind_solutions" , p->astar_parameters .only_behind_solutions );
465
+ updateParam<double >(
466
+ parameters, ns + " distance_heuristic_weight" , p->astar_parameters .distance_heuristic_weight );
445
467
}
446
468
{
447
469
const std::string ns = " start_planner.freespace_planner.rrtstar." ;
@@ -453,6 +475,9 @@ void StartPlannerModuleManager::updateModuleParams(
453
475
parameters, ns + " max_planning_time" , p->rrt_star_parameters .max_planning_time );
454
476
updateParam<double >(parameters, ns + " neighbor_radius" , p->rrt_star_parameters .neighbor_radius );
455
477
updateParam<double >(parameters, ns + " margin" , p->rrt_star_parameters .margin );
478
+ }
479
+
480
+ {
456
481
updateParam<double >(
457
482
parameters, ns + " stop_condition.maximum_deceleration_for_stop" ,
458
483
p->maximum_deceleration_for_stop );
@@ -461,7 +486,6 @@ void StartPlannerModuleManager::updateModuleParams(
461
486
}
462
487
463
488
const std::string base_ns = " start_planner.path_safety_check." ;
464
-
465
489
const std::string ego_path_ns = base_ns + " ego_predicted_path." ;
466
490
467
491
{
@@ -607,6 +631,35 @@ void StartPlannerModuleManager::updateModuleParams(
607
631
updateParam<double >(
608
632
parameters, surround_moving_obstacle_check_ns + " th_moving_obstacle_velocity" ,
609
633
p->th_moving_obstacle_velocity );
634
+
635
+ // ObjectTypesToCheck
636
+ std::string obj_types_ns = surround_moving_obstacle_check_ns + " object_types_to_check." ;
637
+ {
638
+ updateParam<bool >(
639
+ parameters, obj_types_ns + " check_car" ,
640
+ p->surround_moving_obstacles_type_to_check .check_car );
641
+ updateParam<bool >(
642
+ parameters, obj_types_ns + " check_truck" ,
643
+ p->surround_moving_obstacles_type_to_check .check_truck );
644
+ updateParam<bool >(
645
+ parameters, obj_types_ns + " check_bus" ,
646
+ p->surround_moving_obstacles_type_to_check .check_bus );
647
+ updateParam<bool >(
648
+ parameters, obj_types_ns + " check_trailer" ,
649
+ p->surround_moving_obstacles_type_to_check .check_trailer );
650
+ updateParam<bool >(
651
+ parameters, obj_types_ns + " check_unknown" ,
652
+ p->surround_moving_obstacles_type_to_check .check_unknown );
653
+ updateParam<bool >(
654
+ parameters, obj_types_ns + " check_bicycle" ,
655
+ p->surround_moving_obstacles_type_to_check .check_bicycle );
656
+ updateParam<bool >(
657
+ parameters, obj_types_ns + " check_motorcycle" ,
658
+ p->surround_moving_obstacles_type_to_check .check_motorcycle );
659
+ updateParam<bool >(
660
+ parameters, obj_types_ns + " check_pedestrian" ,
661
+ p->surround_moving_obstacles_type_to_check .check_pedestrian );
662
+ }
610
663
}
611
664
612
665
std::string debug_ns = ns + " debug." ;
0 commit comments