Skip to content

Commit 413514b

Browse files
refactor(obstacle_cruise_planner): move slow down params to a clear location (#6644)
move slow down params to a clear location Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent 8a9965a commit 413514b

File tree

2 files changed

+7
-4
lines changed

2 files changed

+7
-4
lines changed

planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@
1616
terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m]
1717
hold_stop_velocity_threshold: 0.01 # The maximum ego velocity to hold stopping [m/s]
1818
hold_stop_distance_threshold: 0.3 # The ego keeps stopping if the distance to stop changes within the threshold [m]
19+
slow_down_min_acc: -1.0 # slow down min deceleration [m/ss]
20+
slow_down_min_jerk: -1.0 # slow down min jerk [m/sss]
1921

2022
nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index
2123
nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index

planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -177,8 +177,8 @@ struct LongitudinalInfo
177177
limit_min_accel = node.declare_parameter<double>("limit.min_acc");
178178
limit_max_jerk = node.declare_parameter<double>("limit.max_jerk");
179179
limit_min_jerk = node.declare_parameter<double>("limit.min_jerk");
180-
slow_down_min_accel = node.declare_parameter<double>("slow_down.min_acc");
181-
slow_down_min_jerk = node.declare_parameter<double>("slow_down.min_jerk");
180+
slow_down_min_accel = node.declare_parameter<double>("common.slow_down_min_acc");
181+
slow_down_min_jerk = node.declare_parameter<double>("common.slow_down_min_jerk");
182182

183183
idling_time = node.declare_parameter<double>("common.idling_time");
184184
min_ego_accel_for_rss = node.declare_parameter<double>("common.min_ego_accel_for_rss");
@@ -205,8 +205,9 @@ struct LongitudinalInfo
205205
tier4_autoware_utils::updateParam<double>(parameters, "limit.max_jerk", limit_max_jerk);
206206
tier4_autoware_utils::updateParam<double>(parameters, "limit.min_jerk", limit_min_jerk);
207207
tier4_autoware_utils::updateParam<double>(
208-
parameters, "slow_down.min_accel", slow_down_min_accel);
209-
tier4_autoware_utils::updateParam<double>(parameters, "slow_down.min_jerk", slow_down_min_jerk);
208+
parameters, "common.slow_down_min_accel", slow_down_min_accel);
209+
tier4_autoware_utils::updateParam<double>(
210+
parameters, "common.slow_down_min_jerk", slow_down_min_jerk);
210211

211212
tier4_autoware_utils::updateParam<double>(parameters, "common.idling_time", idling_time);
212213
tier4_autoware_utils::updateParam<double>(

0 commit comments

Comments
 (0)