@@ -65,10 +65,8 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)
65
65
const auto get_object_param = [&](std::string && ns) {
66
66
ObjectParameter param{};
67
67
param.execute_num = getOrDeclareParameter<int >(*node, ns + " execute_num" );
68
- param.moving_speed_threshold =
69
- getOrDeclareParameter<double >(*node, ns + " moving_speed_threshold" );
70
- param.moving_time_threshold =
71
- getOrDeclareParameter<double >(*node, ns + " moving_time_threshold" );
68
+ param.moving_speed_threshold = getOrDeclareParameter<double >(*node, ns + " th_moving_speed" );
69
+ param.moving_time_threshold = getOrDeclareParameter<double >(*node, ns + " th_moving_time" );
72
70
param.max_expand_ratio = getOrDeclareParameter<double >(*node, ns + " max_expand_ratio" );
73
71
param.envelope_buffer_margin =
74
72
getOrDeclareParameter<double >(*node, ns + " envelope_buffer_margin" );
@@ -121,14 +119,18 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)
121
119
122
120
p.object_check_goal_distance =
123
121
getOrDeclareParameter<double >(*node, ns + " object_check_goal_distance" );
122
+ p.object_last_seen_threshold =
123
+ getOrDeclareParameter<double >(*node, ns + " max_compensation_time" );
124
+ }
125
+
126
+ {
127
+ const std::string ns = " avoidance.target_filtering.parked_vehicle." ;
124
128
p.threshold_distance_object_is_on_center =
125
- getOrDeclareParameter<double >(*node, ns + " threshold_distance_object_is_on_center " );
129
+ getOrDeclareParameter<double >(*node, ns + " th_offset_from_centerline " );
126
130
p.object_check_shiftable_ratio =
127
- getOrDeclareParameter<double >(*node, ns + " object_check_shiftable_ratio " );
131
+ getOrDeclareParameter<double >(*node, ns + " th_shiftable_ratio " );
128
132
p.object_check_min_road_shoulder_width =
129
- getOrDeclareParameter<double >(*node, ns + " object_check_min_road_shoulder_width" );
130
- p.object_last_seen_threshold =
131
- getOrDeclareParameter<double >(*node, ns + " object_last_seen_threshold" );
133
+ getOrDeclareParameter<double >(*node, ns + " min_road_shoulder_width" );
132
134
}
133
135
134
136
{
@@ -137,9 +139,9 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)
137
139
p.closest_distance_to_wait_and_see_for_ambiguous_vehicle =
138
140
getOrDeclareParameter<double >(*node, ns + " closest_distance_to_wait_and_see" );
139
141
p.time_threshold_for_ambiguous_vehicle =
140
- getOrDeclareParameter<double >(*node, ns + " condition.time_threshold " );
142
+ getOrDeclareParameter<double >(*node, ns + " condition.th_stopped_time " );
141
143
p.distance_threshold_for_ambiguous_vehicle =
142
- getOrDeclareParameter<double >(*node, ns + " condition.distance_threshold " );
144
+ getOrDeclareParameter<double >(*node, ns + " condition.th_moving_distance " );
143
145
p.object_ignore_section_traffic_light_in_front_distance =
144
146
getOrDeclareParameter<double >(*node, ns + " ignore_area.traffic_light.front_distance" );
145
147
p.object_ignore_section_crosswalk_in_front_distance =
0 commit comments