Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_launch): add param for configurable lateral_distance #140

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
voxel_grid_x: 0.05 # voxel grid x parameter for filtering pointcloud [m]
voxel_grid_y: 0.05 # voxel grid y parameter for filtering pointcloud [m]
voxel_grid_z: 100000.0 # voxel grid z parameter for filtering pointcloud [m]
use_predicted_objects: False # whether to use predicted objects [-]
publish_obstacle_polygon: False # whether to publish obstacle polygon [-]

stop_planner:
# params for stop position
Expand All @@ -17,7 +19,10 @@

# params for detection area
detection_area:
lateral_margin: 0.0 # margin of vehicle footprint [m]
lateral_margin: 0.0 # margin [m]
vehicle_lateral_margin: 0.0 # margin of vehicle footprint [m]
pedestrian_lateral_margin: 0.0 # margin of pedestrian footprint [m]
unknown_lateral_margin: 0.0 # margin of unknown 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]

Expand All @@ -33,6 +38,9 @@
# 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]
vehicle_lateral_margin: 1.0 # offset from vehicle side edge for expanding the search area of the surrounding point cloud [m]
pedestrian_lateral_margin: 1.0 # offset from pedestrian side edge for expanding the search area of the surrounding point cloud [m]
unknown_lateral_margin: 1.0 # offset from unknown side edge for expanding the search area of the surrounding point cloud [m]

# params for velocity
target_velocity:
Expand Down