Skip to content

Commit

Permalink
sync rc rc/v0.1.1 (tier4#77)
Browse files Browse the repository at this point in the history
* fix center line resolution (tier4#76)

* planning vel limit = 4.5km/h (tier4#75)

* Fix/adjust experiment kashiwanoha (tier4#78)

* change to 5m

* Adjust obstacle stop parameters

Co-authored-by: prds1lg <prod-s1-github@tier4.jp>

Co-authored-by: Hiroki OTA <hiroki.ota@tier4.jp>
Co-authored-by: Kazuki Matsumoto <59071591+kazuki527@users.noreply.github.com>
Co-authored-by: prds1lg <prod-s1-github@tier4.jp>
  • Loading branch information
4 people committed Nov 8, 2021
1 parent 849ecaf commit 2e8344b
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 6 deletions.
2 changes: 1 addition & 1 deletion map_launch/launch/map.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ def generate_launch_description():
remappings=[('output/lanelet2_map', 'vector_map')],
parameters=[
{
'center_line_resolution': 5.0,
'center_line_resolution': 1.0,
'lanelet2_map_path': LaunchConfiguration('lanelet2_map_path'),
}
],
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
/**:
ros__parameters:
max_velocity: 0.85 # max velocity limit [m/s]
max_velocity: 1.25 # max velocity limit [m/s]
max_accel: 0.03 # max acceleration limit [m/ss]
min_decel: -0.05 # min deceleration limit [m/ss]
min_decel: -0.1 # min deceleration limit [m/ss]

# curve parameters
max_lateral_accel: 0.20 # max lateral acceleration limit [m/ss]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
# trajectory total/fixing length
trajectory_length: 20 # total trajectory length[m]
forward_fixing_distance: 20.0 # forward fixing length from base_link[m]
backward_fixing_distance: 1.0 # backward fixing length from base_link[m]
backward_fixing_distance: 5.0 # backward fixing length from base_link[m]

# clearance(distance) when generating trajectory
clearance_from_road: 0.2 # clearance from road boundary[m]
Expand Down
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
/**:
ros__parameters:
stop_planner:
stop_margin: 2.5 # stop margin distance from obstacle on the path [m]
stop_margin: 1.0 # stop margin distance from obstacle on the path [m]
min_behavior_stop_margin: 1.0 # stop margin distance when any other stop point is inserted in stop margin [m]
step_length: 0.1 # step length for pointcloud search range [m]
extend_distance: 1.0 # extend trajectory to consider after goal obstacle in the extend_distance
expand_stop_range: 0.0 # margin of vehicle footprint [m]

slow_down_planner:
slow_down_margin: 2.5 # margin distance from slow down point [m]
slow_down_margin: 1.0 # margin distance from slow down point [m]
expand_slow_down_range: 0.6 # offset from vehicle side edge for expanding the search area of the surrounding point cloud [m]
max_slow_down_vel: 0.7 # max slow down velocity [m/s]
min_slow_down_vel: 0.28 # min slow down velocity [m/s]
Expand Down

0 comments on commit 2e8344b

Please sign in to comment.