Skip to content

Commit ae4176c

Browse files
fix(avoidance): add update param to use rqt reconfigure (autowarefoundation#6759)
* fix(avoidance): add update param to use rqt reconfigure Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * Update planning/behavior_path_avoidance_module/src/manager.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * Update planning/behavior_path_avoidance_module/src/manager.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com>
1 parent a34c039 commit ae4176c

File tree

2 files changed

+102
-0
lines changed

2 files changed

+102
-0
lines changed

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -313,6 +313,10 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
313313
p.use_shorten_margin_immediately =
314314
getOrDeclareParameter<bool>(*node, ns + "use_shorten_margin_immediately");
315315

316+
if (p.policy_approval != "per_shift_line" && p.policy_approval != "per_avoidance_maneuver") {
317+
throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'.");
318+
}
319+
316320
if (p.policy_deceleration != "best_effort" && p.policy_deceleration != "reliable") {
317321
throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'.");
318322
}

planning/behavior_path_avoidance_module/src/manager.cpp

+98
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,76 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
9191
p->upper_distance_for_polygon_expansion);
9292
}
9393

94+
{
95+
const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) {
96+
if (p->object_parameters.count(object_type) == 0) {
97+
return;
98+
}
99+
updateParam<bool>(parameters, ns, p->object_parameters.at(object_type).is_avoidance_target);
100+
};
101+
102+
const std::string ns = "avoidance.target_filtering.";
103+
set_target_flag(ObjectClassification::CAR, ns + "target_type.car");
104+
set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck");
105+
set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer");
106+
set_target_flag(ObjectClassification::BUS, ns + "target_type.bus");
107+
set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian");
108+
set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle");
109+
set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle");
110+
set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown");
111+
112+
updateParam<double>(
113+
parameters, ns + "object_check_goal_distance", p->object_check_goal_distance);
114+
updateParam<double>(
115+
parameters, ns + "object_check_return_pose_distance", p->object_check_return_pose_distance);
116+
updateParam<double>(
117+
parameters, ns + "threshold_distance_object_is_on_center",
118+
p->threshold_distance_object_is_on_center);
119+
updateParam<double>(
120+
parameters, ns + "object_check_shiftable_ratio", p->object_check_shiftable_ratio);
121+
updateParam<double>(
122+
parameters, ns + "object_check_min_road_shoulder_width",
123+
p->object_check_min_road_shoulder_width);
124+
updateParam<double>(
125+
parameters, ns + "object_last_seen_threshold", p->object_last_seen_threshold);
126+
}
127+
128+
{
129+
const std::string ns = "avoidance.target_filtering.detection_area.";
130+
updateParam<bool>(parameters, ns + "static", p->use_static_detection_area);
131+
updateParam<double>(
132+
parameters, ns + "min_forward_distance", p->object_check_min_forward_distance);
133+
updateParam<double>(
134+
parameters, ns + "max_forward_distance", p->object_check_max_forward_distance);
135+
updateParam<double>(parameters, ns + "backward_distance", p->object_check_backward_distance);
136+
}
137+
138+
{
139+
const std::string ns = "avoidance.avoidance.lateral.avoidance_for_ambiguous_vehicle.";
140+
updateParam<bool>(parameters, ns + "enable", p->enable_avoidance_for_ambiguous_vehicle);
141+
updateParam<double>(
142+
parameters, ns + "closest_distance_to_wait_and_see",
143+
p->closest_distance_to_wait_and_see_for_ambiguous_vehicle);
144+
updateParam<double>(
145+
parameters, ns + "condition.time_threshold", p->time_threshold_for_ambiguous_vehicle);
146+
updateParam<double>(
147+
parameters, ns + "condition.distance_threshold", p->distance_threshold_for_ambiguous_vehicle);
148+
updateParam<double>(
149+
parameters, ns + "ignore_area.traffic_light.front_distance",
150+
p->object_ignore_section_traffic_light_in_front_distance);
151+
updateParam<double>(
152+
parameters, ns + "ignore_area.crosswalk.front_distance",
153+
p->object_ignore_section_crosswalk_in_front_distance);
154+
updateParam<double>(
155+
parameters, ns + "ignore_area.crosswalk.behind_distance",
156+
p->object_ignore_section_crosswalk_behind_distance);
157+
}
158+
159+
{
160+
const std::string ns = "avoidance.target_filtering.intersection.";
161+
updateParam<double>(parameters, ns + "yaw_deviation", p->object_check_yaw_deviation);
162+
}
163+
94164
{
95165
const std::string ns = "avoidance.avoidance.lateral.";
96166
updateParam<double>(
@@ -107,6 +177,7 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
107177
const std::string ns = "avoidance.avoidance.longitudinal.";
108178
updateParam<double>(parameters, ns + "min_prepare_time", p->min_prepare_time);
109179
updateParam<double>(parameters, ns + "max_prepare_time", p->max_prepare_time);
180+
updateParam<double>(parameters, ns + "min_prepare_distance", p->min_prepare_distance);
110181
updateParam<double>(parameters, ns + "min_slow_down_speed", p->min_slow_down_speed);
111182
updateParam<double>(parameters, ns + "buf_slow_down_speed", p->buf_slow_down_speed);
112183
}
@@ -117,6 +188,33 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
117188
updateParam<double>(parameters, ns + "stop_buffer", p->stop_buffer);
118189
}
119190

191+
{
192+
const std::string ns = "avoidance.policy.";
193+
updateParam<std::string>(parameters, ns + "make_approval_request", p->policy_approval);
194+
updateParam<std::string>(parameters, ns + "deceleration", p->policy_deceleration);
195+
updateParam<std::string>(parameters, ns + "lateral_margin", p->policy_lateral_margin);
196+
updateParam<bool>(
197+
parameters, ns + "use_shorten_margin_immediately", p->use_shorten_margin_immediately);
198+
199+
if (p->policy_approval != "per_shift_line" && p->policy_approval != "per_avoidance_maneuver") {
200+
RCLCPP_ERROR(
201+
rclcpp::get_logger(__func__),
202+
"invalid policy. please select 'per_shift_line' or 'per_avoidance_maneuver'.");
203+
}
204+
205+
if (p->policy_deceleration != "best_effort" && p->policy_deceleration != "reliable") {
206+
RCLCPP_ERROR(
207+
rclcpp::get_logger(__func__),
208+
"invalid deceleration policy. Please select 'best_effort' or 'reliable'.");
209+
}
210+
211+
if (p->policy_lateral_margin != "best_effort" && p->policy_lateral_margin != "reliable") {
212+
RCLCPP_ERROR(
213+
rclcpp::get_logger(__func__),
214+
"invalid lateral margin policy. Please select 'best_effort' or 'reliable'.");
215+
}
216+
}
217+
120218
{
121219
const std::string ns = "avoidance.constrains.lateral.";
122220

0 commit comments

Comments
 (0)