@@ -49,22 +49,25 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
49
49
p.collision_check_margin_from_front_object =
50
50
node->declare_parameter <double >(ns + " collision_check_margin_from_front_object" );
51
51
p.th_moving_object_velocity = node->declare_parameter <double >(ns + " th_moving_object_velocity" );
52
- p.object_types_to_check_for_path_generation .check_car =
53
- node->declare_parameter <bool >(ns + " check_car" );
54
- p.object_types_to_check_for_path_generation .check_truck =
55
- node->declare_parameter <bool >(ns + " check_truck" );
56
- p.object_types_to_check_for_path_generation .check_bus =
57
- node->declare_parameter <bool >(ns + " check_bus" );
58
- p.object_types_to_check_for_path_generation .check_trailer =
59
- node->declare_parameter <bool >(ns + " check_trailer" );
60
- p.object_types_to_check_for_path_generation .check_unknown =
61
- node->declare_parameter <bool >(ns + " check_unknown" );
62
- p.object_types_to_check_for_path_generation .check_bicycle =
63
- node->declare_parameter <bool >(ns + " check_bicycle" );
64
- p.object_types_to_check_for_path_generation .check_motorcycle =
65
- node->declare_parameter <bool >(ns + " check_motorcycle" );
66
- p.object_types_to_check_for_path_generation .check_pedestrian =
67
- node->declare_parameter <bool >(ns + " check_pedestrian" );
52
+ {
53
+ const std::string ns = " start_planner.object_types_to_check_for_path_generation." ;
54
+ p.object_types_to_check_for_path_generation .check_car =
55
+ node->declare_parameter <bool >(ns + " check_car" );
56
+ p.object_types_to_check_for_path_generation .check_truck =
57
+ node->declare_parameter <bool >(ns + " check_truck" );
58
+ p.object_types_to_check_for_path_generation .check_bus =
59
+ node->declare_parameter <bool >(ns + " check_bus" );
60
+ p.object_types_to_check_for_path_generation .check_trailer =
61
+ node->declare_parameter <bool >(ns + " check_trailer" );
62
+ p.object_types_to_check_for_path_generation .check_unknown =
63
+ node->declare_parameter <bool >(ns + " check_unknown" );
64
+ p.object_types_to_check_for_path_generation .check_bicycle =
65
+ node->declare_parameter <bool >(ns + " check_bicycle" );
66
+ p.object_types_to_check_for_path_generation .check_motorcycle =
67
+ node->declare_parameter <bool >(ns + " check_motorcycle" );
68
+ p.object_types_to_check_for_path_generation .check_pedestrian =
69
+ node->declare_parameter <bool >(ns + " check_pedestrian" );
70
+ }
68
71
p.center_line_path_interval = node->declare_parameter <double >(ns + " center_line_path_interval" );
69
72
// shift pull out
70
73
p.enable_shift_pull_out = node->declare_parameter <bool >(ns + " enable_shift_pull_out" );
0 commit comments