diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml index 93f9d522fb..d707a73bce 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml @@ -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 @@ -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] @@ -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: