Skip to content

Commit d025269

Browse files
committed
fix(safety_check): fix param name
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent c42fa54 commit d025269

File tree

4 files changed

+9
-7
lines changed

4 files changed

+9
-7
lines changed

planning/behavior_path_avoidance_module/config/avoidance.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -187,7 +187,7 @@
187187
time_horizon_for_rear_object: 10.0 # [s]
188188
delay_until_departure: 0.0 # [s]
189189
# rss parameters
190-
steering: "free" # [-] select "fixed" or "free"
190+
extended_polygon_policy: "along_path" # [-] select "rectangle" or "along_path"
191191
expected_front_deceleration: -1.0 # [m/ss]
192192
expected_rear_deceleration: -1.0 # [m/ss]
193193
rear_vehicle_reaction_time: 2.0 # [s]

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -223,7 +223,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
223223
// safety check rss params
224224
{
225225
const std::string ns = "avoidance.safety_check.";
226-
p.rss_params.steering = getOrDeclareParameter<std::string>(*node, ns + "steering");
226+
p.rss_params.extended_polygon_policy =
227+
getOrDeclareParameter<std::string>(*node, ns + "extended_polygon_policy");
227228
p.rss_params.longitudinal_distance_min_threshold =
228229
getOrDeclareParameter<double>(*node, ns + "longitudinal_distance_min_threshold");
229230
p.rss_params.longitudinal_velocity_delta_time =

planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -126,8 +126,9 @@ struct TargetObjectsOnLane
126126
*/
127127
struct RSSparams
128128
{
129-
std::string steering{"fixed"}; ///< Policy to create collision check polygon.
130-
/// possible values: ["fixed", "free"]
129+
std::string extended_polygon_policy{
130+
"rectangle"}; ///< Policy to create collision check polygon.
131+
///< possible values: ["rectangle", "along_path"]
131132
double rear_vehicle_reaction_time{0.0}; ///< Reaction time of the rear vehicle.
132133
double rear_vehicle_safety_time_margin{0.0}; ///< Safety time margin for the rear vehicle.
133134
double lateral_distance_max_threshold{0.0}; ///< Maximum threshold for lateral distance.

planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -636,18 +636,18 @@ std::vector<Polygon2d> getCollidedPolygons(
636636
return ego_polygon;
637637
}
638638

639-
if (rss_parameters.steering == "fixed") {
639+
if (rss_parameters.extended_polygon_policy == "rectangle") {
640640
return createExtendedPolygon(
641641
ego_pose, ego_vehicle_info, lon_offset, lat_margin, is_stopped_object, debug);
642642
}
643643

644-
if (rss_parameters.steering == "free") {
644+
if (rss_parameters.extended_polygon_policy == "along_path") {
645645
return createExtendedPolygonAlongPath(
646646
planned_path, ego_pose, ego_vehicle_info, lon_offset, lat_margin, is_stopped_object,
647647
debug);
648648
}
649649

650-
throw std::domain_error("invalid rss parameter. please select 'fixed' or 'free'.");
650+
throw std::domain_error("invalid rss parameter. please select 'rectangle' or 'along_path'.");
651651
}();
652652
const auto & extended_obj_polygon =
653653
is_object_front

0 commit comments

Comments
 (0)