Skip to content

Commit

Permalink
refactor(obstacle_cruise_planner): move slow down params to a clear l…
Browse files Browse the repository at this point in the history
…ocation (#6644)

move slow down params to a clear location

Signed-off-by: Daniel Sanchez <[email protected]>
  • Loading branch information
danielsanchezaran authored Mar 18, 2024
1 parent 8a9965a commit 413514b
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@
terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m]
hold_stop_velocity_threshold: 0.01 # The maximum ego velocity to hold stopping [m/s]
hold_stop_distance_threshold: 0.3 # The ego keeps stopping if the distance to stop changes within the threshold [m]
slow_down_min_acc: -1.0 # slow down min deceleration [m/ss]
slow_down_min_jerk: -1.0 # slow down min jerk [m/sss]

nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index
nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -177,8 +177,8 @@ struct LongitudinalInfo
limit_min_accel = node.declare_parameter<double>("limit.min_acc");
limit_max_jerk = node.declare_parameter<double>("limit.max_jerk");
limit_min_jerk = node.declare_parameter<double>("limit.min_jerk");
slow_down_min_accel = node.declare_parameter<double>("slow_down.min_acc");
slow_down_min_jerk = node.declare_parameter<double>("slow_down.min_jerk");
slow_down_min_accel = node.declare_parameter<double>("common.slow_down_min_acc");
slow_down_min_jerk = node.declare_parameter<double>("common.slow_down_min_jerk");

idling_time = node.declare_parameter<double>("common.idling_time");
min_ego_accel_for_rss = node.declare_parameter<double>("common.min_ego_accel_for_rss");
Expand All @@ -205,8 +205,9 @@ struct LongitudinalInfo
tier4_autoware_utils::updateParam<double>(parameters, "limit.max_jerk", limit_max_jerk);
tier4_autoware_utils::updateParam<double>(parameters, "limit.min_jerk", limit_min_jerk);
tier4_autoware_utils::updateParam<double>(
parameters, "slow_down.min_accel", slow_down_min_accel);
tier4_autoware_utils::updateParam<double>(parameters, "slow_down.min_jerk", slow_down_min_jerk);
parameters, "common.slow_down_min_accel", slow_down_min_accel);
tier4_autoware_utils::updateParam<double>(
parameters, "common.slow_down_min_jerk", slow_down_min_jerk);

tier4_autoware_utils::updateParam<double>(parameters, "common.idling_time", idling_time);
tier4_autoware_utils::updateParam<double>(
Expand Down

0 comments on commit 413514b

Please sign in to comment.