Skip to content

Commit

Permalink
refactor(planning_launch): update params name for readability (#458)
Browse files Browse the repository at this point in the history
* refactor(planning_launch): update params name for readability

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

* refactor(planning_launch): add params to config

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
  • Loading branch information
satoshi-ota committed Sep 6, 2022
1 parent ef611e0 commit 3145c5d
Showing 1 changed file with 43 additions and 22 deletions.
Original file line number Diff line number Diff line change
@@ -1,28 +1,49 @@
/**:
ros__parameters:
hunting_threshold: 0.5 # even if the obstacle disappears, the stop judgment continues for hunting_threshold [s]
hunting_threshold: 0.5 # even if the obstacle disappears, the stop judgment continues for hunting_threshold [s]
lowpass_gain: 0.9 # gain parameter for low pass filter [-]
max_velocity: 20.0 # max velocity [m/s]
enable_slow_down: False # whether to use slow down planner [-]

stop_planner:
stop_margin: 5.0 # stop margin distance from obstacle on the path [m]
min_behavior_stop_margin: 5.0 # stop margin distance when any other stop point is inserted in stop margin [m]
step_length: 1.0 # step length for pointcloud search range [m]
extend_distance: 0.0 # extend trajectory to consider after goal obstacle in the extend_distance
expand_stop_range: 0.0 # margin of vehicle footprint [m]
hold_stop_margin_distance: 0.0 # the ego keeps stopping if the ego is in this margin [m]
# params for stop position
stop_position:
max_longitudinal_margin: 5.0 # stop margin distance from obstacle on the path [m]
min_longitudinal_margin: 5.0 # stop margin distance when any other stop point is inserted in stop margin [m]
hold_stop_margin_distance: 0.0 # the ego keeps stopping if the ego is in this margin [m]

# params for detection area
detection_area:
lateral_margin: 0.0 # margin of vehicle footprint [m]
step_length: 1.0 # step length for pointcloud search range [m]
extend_distance: 0.0 # extend trajectory to consider after goal obstacle in the extend_distance [m]


slow_down_planner:
# slow down planner parameters
forward_margin: 5.0 # margin distance from slow down point to vehicle front [m]
backward_margin: 0.0 # margin distance from slow down point to vehicle rear [m]
expand_slow_down_range: 1.0 # offset from vehicle side edge for expanding the search area of the surrounding point cloud [m]
max_slow_down_vel: 1.38 # max slow down velocity [m/s]
min_slow_down_vel: 0.28 # min slow down velocity [m/s]

# slow down constraint parameters
consider_constraints: False # set "True", if no decel plan found under jerk/dec constrains, relax target slow down vel
forward_margin_min: 1.0 # min margin for relaxing slow down margin [m/s]
forward_margin_span: -0.1 # fineness param for relaxing slow down margin [m/s]
jerk_min_slow_down: -0.6 # min slow down jerk constraint [m/sss]
jerk_span: -0.01 # fineness param for planning deceleration jerk [m/sss]
jerk_start: -0.1 # init jerk used for deceleration planning [m/sss]
slow_down_vel: 1.38 # target slow down velocity [m/s]
# params for slow down section
slow_down_section:
longitudinal_forward_margin: 5.0 # margin distance from slow down point to vehicle front [m]
longitudinal_backward_margin: 0.0 # margin distance from slow down point to vehicle rear [m]
longitudinal_margin_span: -0.1 # fineness param for relaxing slow down margin (use this param if consider_constraints is True) [m/s]
min_longitudinal_forward_margin: 1.0 # min margin for relaxing slow down margin (use this param if consider_constraints is True) [m/s]

# params for detection area
detection_area:
lateral_margin: 1.0 # offset from vehicle side edge for expanding the search area of the surrounding point cloud [m]

# params for velocity
target_velocity:
max_slow_down_velocity: 1.38 # max slow down velocity (use this param if consider_constraints is False)[m/s]
min_slow_down_velocity: 0.28 # min slow down velocity (use this param if consider_constraints is False)[m/s]
slow_down_velocity: 1.38 # target slow down velocity (use this param if consider_constraints is True)[m/s]

# params for deceleration constraints (use this param if consider_constraints is True)
constraints:
jerk_min_slow_down: -0.6 # min slow down jerk constraint [m/sss]
jerk_span: -0.01 # fineness param for planning deceleration jerk [m/sss]
jerk_start: -0.1 # init jerk used for deceleration planning [m/sss]

# others
consider_constraints: False # set "True", if no decel plan found under jerk/dec constrains, relax target slow down vel [-]
velocity_threshold_decel_complete: 0.2 # use for judge whether the ego velocity converges the target slow down velocity [m/s]
acceleration_threshold_decel_complete: 0.1 # use for judge whether the ego velocity converges the target slow down velocity [m/ss]

0 comments on commit 3145c5d

Please sign in to comment.