@@ -31,21 +31,78 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
31
31
32
32
StartPlannerParameters p;
33
33
34
- const std::string ns = " start_planner." ;
35
-
36
- p.th_arrived_distance = node->declare_parameter <double >(ns + " th_arrived_distance" );
37
- p.th_stopped_velocity = node->declare_parameter <double >(ns + " th_stopped_velocity" );
38
- p.th_stopped_time = node->declare_parameter <double >(ns + " th_stopped_time" );
39
- p.prepare_time_before_start = node->declare_parameter <double >(ns + " prepare_time_before_start" );
40
- p.th_distance_to_middle_of_the_road =
41
- node->declare_parameter <double >(ns + " th_distance_to_middle_of_the_road" );
42
- p.extra_width_margin_for_rear_obstacle =
43
- node->declare_parameter <double >(ns + " extra_width_margin_for_rear_obstacle" );
44
- p.collision_check_margins =
45
- node->declare_parameter <std::vector<double >>(ns + " collision_check_margins" );
46
- p.collision_check_margin_from_front_object =
47
- node->declare_parameter <double >(ns + " collision_check_margin_from_front_object" );
48
- p.th_moving_object_velocity = node->declare_parameter <double >(ns + " th_moving_object_velocity" );
34
+ {
35
+ const std::string ns = " start_planner." ;
36
+
37
+ p.th_arrived_distance = node->declare_parameter <double >(ns + " th_arrived_distance" );
38
+ p.th_stopped_velocity = node->declare_parameter <double >(ns + " th_stopped_velocity" );
39
+ p.th_stopped_time = node->declare_parameter <double >(ns + " th_stopped_time" );
40
+ p.prepare_time_before_start = node->declare_parameter <double >(ns + " prepare_time_before_start" );
41
+ p.th_distance_to_middle_of_the_road =
42
+ node->declare_parameter <double >(ns + " th_distance_to_middle_of_the_road" );
43
+ p.extra_width_margin_for_rear_obstacle =
44
+ node->declare_parameter <double >(ns + " extra_width_margin_for_rear_obstacle" );
45
+ p.collision_check_margins =
46
+ node->declare_parameter <std::vector<double >>(ns + " collision_check_margins" );
47
+ p.collision_check_margin_from_front_object =
48
+ node->declare_parameter <double >(ns + " collision_check_margin_from_front_object" );
49
+ p.th_moving_object_velocity = node->declare_parameter <double >(ns + " th_moving_object_velocity" );
50
+ p.center_line_path_interval = node->declare_parameter <double >(ns + " center_line_path_interval" );
51
+ // shift pull out
52
+ p.enable_shift_pull_out = node->declare_parameter <bool >(ns + " enable_shift_pull_out" );
53
+ p.check_shift_path_lane_departure =
54
+ node->declare_parameter <bool >(ns + " check_shift_path_lane_departure" );
55
+ p.allow_check_shift_path_lane_departure_override =
56
+ node->declare_parameter <bool >(ns + " allow_check_shift_path_lane_departure_override" );
57
+ p.shift_collision_check_distance_from_end =
58
+ node->declare_parameter <double >(ns + " shift_collision_check_distance_from_end" );
59
+ p.minimum_shift_pull_out_distance =
60
+ node->declare_parameter <double >(ns + " minimum_shift_pull_out_distance" );
61
+ p.lateral_acceleration_sampling_num =
62
+ node->declare_parameter <int >(ns + " lateral_acceleration_sampling_num" );
63
+ p.lateral_jerk = node->declare_parameter <double >(ns + " lateral_jerk" );
64
+ p.maximum_lateral_acc = node->declare_parameter <double >(ns + " maximum_lateral_acc" );
65
+ p.minimum_lateral_acc = node->declare_parameter <double >(ns + " minimum_lateral_acc" );
66
+ p.maximum_curvature = node->declare_parameter <double >(ns + " maximum_curvature" );
67
+ p.end_pose_curvature_threshold =
68
+ node->declare_parameter <double >(ns + " end_pose_curvature_threshold" );
69
+ p.maximum_longitudinal_deviation =
70
+ node->declare_parameter <double >(ns + " maximum_longitudinal_deviation" );
71
+ // geometric pull out
72
+ p.enable_geometric_pull_out = node->declare_parameter <bool >(ns + " enable_geometric_pull_out" );
73
+ p.geometric_collision_check_distance_from_end =
74
+ node->declare_parameter <double >(ns + " geometric_collision_check_distance_from_end" );
75
+ p.divide_pull_out_path = node->declare_parameter <bool >(ns + " divide_pull_out_path" );
76
+ p.parallel_parking_parameters .pull_out_velocity =
77
+ node->declare_parameter <double >(ns + " geometric_pull_out_velocity" );
78
+ p.parallel_parking_parameters .pull_out_arc_path_interval =
79
+ node->declare_parameter <double >(ns + " arc_path_interval" );
80
+ p.parallel_parking_parameters .pull_out_lane_departure_margin =
81
+ node->declare_parameter <double >(ns + " lane_departure_margin" );
82
+ p.lane_departure_check_expansion_margin =
83
+ node->declare_parameter <double >(ns + " lane_departure_check_expansion_margin" );
84
+ p.parallel_parking_parameters .pull_out_max_steer_angle =
85
+ node->declare_parameter <double >(ns + " pull_out_max_steer_angle" ); // 15deg
86
+ p.parallel_parking_parameters .center_line_path_interval =
87
+ p.center_line_path_interval ; // for geometric parallel parking
88
+ // search start pose backward
89
+ p.search_priority = node->declare_parameter <std::string>(
90
+ ns + " search_priority" ); // "efficient_path" or "short_back_distance"
91
+ p.enable_back = node->declare_parameter <bool >(ns + " enable_back" );
92
+ p.backward_velocity = node->declare_parameter <double >(ns + " backward_velocity" );
93
+ p.max_back_distance = node->declare_parameter <double >(ns + " max_back_distance" );
94
+ p.backward_search_resolution =
95
+ node->declare_parameter <double >(ns + " backward_search_resolution" );
96
+ p.backward_path_update_duration =
97
+ node->declare_parameter <double >(ns + " backward_path_update_duration" );
98
+ p.ignore_distance_from_lane_end =
99
+ node->declare_parameter <double >(ns + " ignore_distance_from_lane_end" );
100
+ // stop condition
101
+ p.maximum_deceleration_for_stop =
102
+ node->declare_parameter <double >(ns + " stop_condition.maximum_deceleration_for_stop" );
103
+ p.maximum_jerk_for_stop =
104
+ node->declare_parameter <double >(ns + " stop_condition.maximum_jerk_for_stop" );
105
+ }
49
106
{
50
107
const std::string ns = " start_planner.object_types_to_check_for_path_generation." ;
51
108
p.object_types_to_check_for_path_generation .check_car =
@@ -65,55 +122,6 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
65
122
p.object_types_to_check_for_path_generation .check_pedestrian =
66
123
node->declare_parameter <bool >(ns + " check_pedestrian" );
67
124
}
68
- p.center_line_path_interval = node->declare_parameter <double >(ns + " center_line_path_interval" );
69
- // shift pull out
70
- p.enable_shift_pull_out = node->declare_parameter <bool >(ns + " enable_shift_pull_out" );
71
- p.check_shift_path_lane_departure =
72
- node->declare_parameter <bool >(ns + " check_shift_path_lane_departure" );
73
- p.allow_check_shift_path_lane_departure_override =
74
- node->declare_parameter <bool >(ns + " allow_check_shift_path_lane_departure_override" );
75
- p.shift_collision_check_distance_from_end =
76
- node->declare_parameter <double >(ns + " shift_collision_check_distance_from_end" );
77
- p.minimum_shift_pull_out_distance =
78
- node->declare_parameter <double >(ns + " minimum_shift_pull_out_distance" );
79
- p.lateral_acceleration_sampling_num =
80
- node->declare_parameter <int >(ns + " lateral_acceleration_sampling_num" );
81
- p.lateral_jerk = node->declare_parameter <double >(ns + " lateral_jerk" );
82
- p.maximum_lateral_acc = node->declare_parameter <double >(ns + " maximum_lateral_acc" );
83
- p.minimum_lateral_acc = node->declare_parameter <double >(ns + " minimum_lateral_acc" );
84
- p.maximum_curvature = node->declare_parameter <double >(ns + " maximum_curvature" );
85
- p.end_pose_curvature_threshold =
86
- node->declare_parameter <double >(ns + " end_pose_curvature_threshold" );
87
- p.maximum_longitudinal_deviation =
88
- node->declare_parameter <double >(ns + " maximum_longitudinal_deviation" );
89
- // geometric pull out
90
- p.enable_geometric_pull_out = node->declare_parameter <bool >(ns + " enable_geometric_pull_out" );
91
- p.geometric_collision_check_distance_from_end =
92
- node->declare_parameter <double >(ns + " geometric_collision_check_distance_from_end" );
93
- p.divide_pull_out_path = node->declare_parameter <bool >(ns + " divide_pull_out_path" );
94
- p.parallel_parking_parameters .pull_out_velocity =
95
- node->declare_parameter <double >(ns + " geometric_pull_out_velocity" );
96
- p.parallel_parking_parameters .pull_out_arc_path_interval =
97
- node->declare_parameter <double >(ns + " arc_path_interval" );
98
- p.parallel_parking_parameters .pull_out_lane_departure_margin =
99
- node->declare_parameter <double >(ns + " lane_departure_margin" );
100
- p.lane_departure_check_expansion_margin =
101
- node->declare_parameter <double >(ns + " lane_departure_check_expansion_margin" );
102
- p.parallel_parking_parameters .pull_out_max_steer_angle =
103
- node->declare_parameter <double >(ns + " pull_out_max_steer_angle" ); // 15deg
104
- p.parallel_parking_parameters .center_line_path_interval =
105
- p.center_line_path_interval ; // for geometric parallel parking
106
- // search start pose backward
107
- p.search_priority = node->declare_parameter <std::string>(
108
- ns + " search_priority" ); // "efficient_path" or "short_back_distance"
109
- p.enable_back = node->declare_parameter <bool >(ns + " enable_back" );
110
- p.backward_velocity = node->declare_parameter <double >(ns + " backward_velocity" );
111
- p.max_back_distance = node->declare_parameter <double >(ns + " max_back_distance" );
112
- p.backward_search_resolution = node->declare_parameter <double >(ns + " backward_search_resolution" );
113
- p.backward_path_update_duration =
114
- node->declare_parameter <double >(ns + " backward_path_update_duration" );
115
- p.ignore_distance_from_lane_end =
116
- node->declare_parameter <double >(ns + " ignore_distance_from_lane_end" );
117
125
// freespace planner general params
118
126
{
119
127
const std::string ns = " start_planner.freespace_planner." ;
@@ -184,19 +192,10 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
184
192
p.rrt_star_parameters .margin = node->declare_parameter <double >(ns + " margin" );
185
193
}
186
194
187
- // stop condition
188
- {
189
- p.maximum_deceleration_for_stop =
190
- node->declare_parameter <double >(ns + " stop_condition.maximum_deceleration_for_stop" );
191
- p.maximum_jerk_for_stop =
192
- node->declare_parameter <double >(ns + " stop_condition.maximum_jerk_for_stop" );
193
- }
194
-
195
195
const std::string base_ns = " start_planner.path_safety_check." ;
196
-
197
196
// EgoPredictedPath
198
- const std::string ego_path_ns = base_ns + " ego_predicted_path." ;
199
197
{
198
+ const std::string ego_path_ns = base_ns + " ego_predicted_path." ;
200
199
p.ego_predicted_path_params .min_velocity =
201
200
node->declare_parameter <double >(ego_path_ns + " min_velocity" );
202
201
p.ego_predicted_path_params .acceleration =
@@ -210,7 +209,6 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
210
209
p.ego_predicted_path_params .delay_until_departure =
211
210
node->declare_parameter <double >(ego_path_ns + " delay_until_departure" );
212
211
}
213
-
214
212
// ObjectFilteringParams
215
213
const std::string obj_filter_ns = base_ns + " target_filtering." ;
216
214
{
@@ -235,10 +233,9 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
235
233
p.objects_filtering_params .use_predicted_path_outside_lanelet =
236
234
node->declare_parameter <bool >(obj_filter_ns + " use_predicted_path_outside_lanelet" );
237
235
}
238
-
239
236
// ObjectTypesToCheck
240
- const std::string obj_types_ns = obj_filter_ns + " object_types_to_check." ;
241
237
{
238
+ const std::string obj_types_ns = obj_filter_ns + " object_types_to_check." ;
242
239
p.objects_filtering_params .object_types_to_check .check_car =
243
240
node->declare_parameter <bool >(obj_types_ns + " check_car" );
244
241
p.objects_filtering_params .object_types_to_check .check_truck =
@@ -256,10 +253,9 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
256
253
p.objects_filtering_params .object_types_to_check .check_pedestrian =
257
254
node->declare_parameter <bool >(obj_types_ns + " check_pedestrian" );
258
255
}
259
-
260
256
// ObjectLaneConfiguration
261
- const std::string obj_lane_ns = obj_filter_ns + " object_lane_configuration." ;
262
257
{
258
+ const std::string obj_lane_ns = obj_filter_ns + " object_lane_configuration." ;
263
259
p.objects_filtering_params .object_lane_configuration .check_current_lane =
264
260
node->declare_parameter <bool >(obj_lane_ns + " check_current_lane" );
265
261
p.objects_filtering_params .object_lane_configuration .check_right_lane =
@@ -271,7 +267,6 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
271
267
p.objects_filtering_params .object_lane_configuration .check_other_lane =
272
268
node->declare_parameter <bool >(obj_lane_ns + " check_other_lane" );
273
269
}
274
-
275
270
// SafetyCheckParams
276
271
const std::string safety_check_ns = base_ns + " safety_check_params." ;
277
272
{
@@ -288,10 +283,9 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
288
283
p.safety_check_params .collision_check_yaw_diff_threshold =
289
284
node->declare_parameter <double >(safety_check_ns + " collision_check_yaw_diff_threshold" );
290
285
}
291
-
292
286
// RSSparams
293
- const std::string rss_ns = safety_check_ns + " rss_params." ;
294
287
{
288
+ const std::string rss_ns = safety_check_ns + " rss_params." ;
295
289
p.safety_check_params .rss_params .rear_vehicle_reaction_time =
296
290
node->declare_parameter <double >(rss_ns + " rear_vehicle_reaction_time" );
297
291
p.safety_check_params .rss_params .rear_vehicle_safety_time_margin =
@@ -305,17 +299,17 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
305
299
p.safety_check_params .rss_params .extended_polygon_policy =
306
300
node->declare_parameter <std::string>(rss_ns + " extended_polygon_policy" );
307
301
}
308
-
309
302
// surround moving obstacle check
310
- std::string surround_moving_obstacle_check_ns = ns + " surround_moving_obstacle_check." ;
311
303
{
304
+ const std::string surround_moving_obstacle_check_ns =
305
+ " start_planner.surround_moving_obstacle_check." ;
312
306
p.search_radius =
313
307
node->declare_parameter <double >(surround_moving_obstacle_check_ns + " search_radius" );
314
308
p.th_moving_obstacle_velocity = node->declare_parameter <double >(
315
309
surround_moving_obstacle_check_ns + " th_moving_obstacle_velocity" );
316
310
// ObjectTypesToCheck
317
- std::string obj_types_ns = surround_moving_obstacle_check_ns + " object_types_to_check." ;
318
311
{
312
+ const std::string obj_types_ns = surround_moving_obstacle_check_ns + " object_types_to_check." ;
319
313
p.surround_moving_obstacles_type_to_check .check_car =
320
314
node->declare_parameter <bool >(obj_types_ns + " check_car" );
321
315
p.surround_moving_obstacles_type_to_check .check_truck =
@@ -336,8 +330,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
336
330
}
337
331
338
332
// debug
339
- std::string debug_ns = ns + " debug." ;
340
333
{
334
+ const std::string debug_ns = " start_planner.debug." ;
341
335
p.print_debug_info = node->declare_parameter <bool >(debug_ns + " print_debug_info" );
342
336
}
343
337
@@ -361,9 +355,8 @@ void StartPlannerModuleManager::updateModuleParams(
361
355
362
356
auto & p = parameters_;
363
357
364
- const std::string ns = " start_planner." ;
365
-
366
358
{
359
+ const std::string ns = " start_planner." ;
367
360
updateParam<double >(parameters, ns + " th_arrived_distance" , p->th_arrived_distance );
368
361
updateParam<double >(parameters, ns + " th_stopped_velocity" , p->th_stopped_velocity );
369
362
updateParam<double >(parameters, ns + " th_stopped_time" , p->th_stopped_time );
@@ -458,6 +451,11 @@ void StartPlannerModuleManager::updateModuleParams(
458
451
parameters, ns + " backward_path_update_duration" , p->backward_path_update_duration );
459
452
updateParam<double >(
460
453
parameters, ns + " ignore_distance_from_lane_end" , p->ignore_distance_from_lane_end );
454
+ updateParam<double >(
455
+ parameters, ns + " stop_condition.maximum_deceleration_for_stop" ,
456
+ p->maximum_deceleration_for_stop );
457
+ updateParam<double >(
458
+ parameters, ns + " stop_condition.maximum_jerk_for_stop" , p->maximum_jerk_for_stop );
461
459
}
462
460
{
463
461
const std::string ns = " start_planner.freespace_planner." ;
@@ -525,6 +523,7 @@ void StartPlannerModuleManager::updateModuleParams(
525
523
updateParam<double >(
526
524
parameters, ns + " distance_heuristic_weight" , p->astar_parameters .distance_heuristic_weight );
527
525
}
526
+
528
527
{
529
528
const std::string ns = " start_planner.freespace_planner.rrtstar." ;
530
529
@@ -537,14 +536,6 @@ void StartPlannerModuleManager::updateModuleParams(
537
536
updateParam<double >(parameters, ns + " margin" , p->rrt_star_parameters .margin );
538
537
}
539
538
540
- {
541
- updateParam<double >(
542
- parameters, ns + " stop_condition.maximum_deceleration_for_stop" ,
543
- p->maximum_deceleration_for_stop );
544
- updateParam<double >(
545
- parameters, ns + " stop_condition.maximum_jerk_for_stop" , p->maximum_jerk_for_stop );
546
- }
547
-
548
539
const std::string base_ns = " start_planner.path_safety_check." ;
549
540
const std::string ego_path_ns = base_ns + " ego_predicted_path." ;
550
541
@@ -567,7 +558,6 @@ void StartPlannerModuleManager::updateModuleParams(
567
558
}
568
559
569
560
const std::string obj_filter_ns = base_ns + " target_filtering." ;
570
-
571
561
{
572
562
updateParam<double >(
573
563
parameters, obj_filter_ns + " safety_check_time_horizon" ,
@@ -601,9 +591,8 @@ void StartPlannerModuleManager::updateModuleParams(
601
591
p->objects_filtering_params .use_predicted_path_outside_lanelet );
602
592
}
603
593
604
- const std::string obj_types_ns = obj_filter_ns + " object_types_to_check." ;
605
-
606
594
{
595
+ const std::string obj_types_ns = obj_filter_ns + " object_types_to_check." ;
607
596
updateParam<bool >(
608
597
parameters, obj_types_ns + " check_car" ,
609
598
p->objects_filtering_params .object_types_to_check .check_car );
@@ -629,8 +618,8 @@ void StartPlannerModuleManager::updateModuleParams(
629
618
parameters, obj_types_ns + " check_pedestrian" ,
630
619
p->objects_filtering_params .object_types_to_check .check_pedestrian );
631
620
}
632
- const std::string obj_lane_ns = obj_filter_ns + " object_lane_configuration." ;
633
621
622
+ const std::string obj_lane_ns = obj_filter_ns + " object_lane_configuration." ;
634
623
{
635
624
updateParam<bool >(
636
625
parameters, obj_lane_ns + " check_current_lane" ,
@@ -648,6 +637,7 @@ void StartPlannerModuleManager::updateModuleParams(
648
637
parameters, obj_lane_ns + " check_other_lane" ,
649
638
p->objects_filtering_params .object_lane_configuration .check_other_lane );
650
639
}
640
+
651
641
const std::string safety_check_ns = base_ns + " safety_check_params." ;
652
642
{
653
643
updateParam<bool >(
@@ -669,8 +659,9 @@ void StartPlannerModuleManager::updateModuleParams(
669
659
parameters, safety_check_ns + " collision_check_yaw_diff_threshold" ,
670
660
p->safety_check_params .collision_check_yaw_diff_threshold );
671
661
}
672
- const std::string rss_ns = safety_check_ns + " rss_params. " ;
662
+
673
663
{
664
+ const std::string rss_ns = safety_check_ns + " rss_params." ;
674
665
updateParam<double >(
675
666
parameters, rss_ns + " rear_vehicle_reaction_time" ,
676
667
p->safety_check_params .rss_params .rear_vehicle_reaction_time );
@@ -690,17 +681,18 @@ void StartPlannerModuleManager::updateModuleParams(
690
681
parameters, rss_ns + " extended_polygon_policy" ,
691
682
p->safety_check_params .rss_params .extended_polygon_policy );
692
683
}
693
- std::string surround_moving_obstacle_check_ns = ns + " surround_moving_obstacle_check." ;
694
684
{
685
+ const std::string surround_moving_obstacle_check_ns =
686
+ " start_planner.surround_moving_obstacle_check." ;
695
687
updateParam<double >(
696
688
parameters, surround_moving_obstacle_check_ns + " search_radius" , p->search_radius );
697
689
updateParam<double >(
698
690
parameters, surround_moving_obstacle_check_ns + " th_moving_obstacle_velocity" ,
699
691
p->th_moving_obstacle_velocity );
700
692
701
693
// ObjectTypesToCheck
702
- std::string obj_types_ns = surround_moving_obstacle_check_ns + " object_types_to_check." ;
703
694
{
695
+ std::string obj_types_ns = surround_moving_obstacle_check_ns + " object_types_to_check." ;
704
696
updateParam<bool >(
705
697
parameters, obj_types_ns + " check_car" ,
706
698
p->surround_moving_obstacles_type_to_check .check_car );
@@ -728,8 +720,8 @@ void StartPlannerModuleManager::updateModuleParams(
728
720
}
729
721
}
730
722
731
- std::string debug_ns = ns + " debug." ;
732
723
{
724
+ const std::string debug_ns = " start_planner.debug." ;
733
725
updateParam<bool >(parameters, debug_ns + " print_debug_info" , p->print_debug_info );
734
726
}
735
727
0 commit comments