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

chore: sync awf-latest #359

Merged
merged 3 commits into from
Mar 27, 2024
Merged
Show file tree
Hide file tree
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 @@ -2,15 +2,18 @@
ros__parameters:
run_out:
detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points
target_obstacle_types: ["PEDESTRIAN", "BICYCLE", "MOTORCYCLE"] # [-] Obstacle types considered by this module
use_partition_lanelet: true # [-] whether to use partition lanelet map data
suppress_on_crosswalk: true # [-] whether to suppress on crosswalk lanelet
use_ego_cut_line: true # [-] filter obstacles that pass the backside of ego: if a dynamic obstacle's predicted path intersects this line, it is ignored
specify_decel_jerk: true # [-] whether to specify jerk when ego decelerates
stop_margin: 2.5 # [m] the vehicle decelerates to be able to stop with this margin
passing_margin: 1.1 # [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin
deceleration_jerk: -0.3 # [m/s^3] ego decelerates with this jerk when stopping for obstacles
detection_distance: 45.0 # [m] ahead distance from ego to detect the obstacles
detection_span: 1.0 # [m] calculate collision with this span to reduce calculation time
min_vel_ego_kmph: 3.6 # [km/h] min velocity to calculate time to collision
ego_cut_line_length: 3.0 # The width of the ego's cut line

# Parameter to create abstracted dynamic obstacles
dynamic_obstacle:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
<arg name="launch_dummy_perception"/>
<arg name="launch_dummy_vehicle"/>
<arg name="launch_dummy_localization"/>
<arg name="launch_dummy_doors"/>
<arg name="launch_diagnostic_converter"/>
<arg name="perception/enable_detection_failure"/>
<arg name="perception/enable_object_recognition"/>
Expand All @@ -17,6 +18,7 @@
<arg name="launch_dummy_perception" value="$(var launch_dummy_perception)"/>
<arg name="launch_dummy_vehicle" value="$(var launch_dummy_vehicle)"/>
<arg name="launch_dummy_localization" value="$(var launch_dummy_localization)"/>
<arg name="launch_dummy_doors" value="$(var launch_dummy_doors)"/>
<arg name="launch_diagnostic_converter" value="$(var launch_diagnostic_converter)"/>
<arg name="perception/enable_detection_failure" value="$(var perception/enable_detection_failure)"/>
<arg name="perception/enable_object_recognition" value="$(var perception/enable_object_recognition)"/>
Expand Down
2 changes: 2 additions & 0 deletions autoware_launch/launch/planning_simulator.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
<let name="rviz_initial_pose_auto_fix_target" value="vector_map"/>
<let name="gnss_initial_pose_auto_fix_target" value="vector_map"/>
<!-- System -->
<arg name="launch_dummy_doors" default="true" description="launch dummy doors simulation"/>
<arg name="launch_system_monitor" default="false" description="launch system monitor"/>
<arg name="launch_dummy_diag_publisher" default="false" description="launch dummy diag publisher"/>
<!-- Scenario simulation -->
Expand Down Expand Up @@ -86,6 +87,7 @@
<arg name="launch_dummy_perception" value="$(var launch_dummy_perception)"/>
<arg name="launch_dummy_vehicle" value="$(var launch_dummy_vehicle)"/>
<arg name="launch_dummy_localization" value="$(var launch_dummy_localization)"/>
<arg name="launch_dummy_doors" value="$(var launch_dummy_doors)"/>
<arg name="launch_diagnostic_converter" value="$(var launch_diagnostic_converter)"/>
<arg name="perception/enable_detection_failure" value="$(var perception/enable_detection_failure)"/>
<arg name="perception/enable_object_recognition" value="$(var perception/enable_object_recognition)"/>
Expand Down
Loading