diff --git a/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml index 9512ed388d..59e25cbc5d 100644 --- a/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml +++ b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml @@ -3,6 +3,10 @@ # Node update_rate: 10.0 visualize_lanelet: false + include_right_lanes: false + include_left_lanes: false + include_opposite_lanes: false + include_conflicting_lanes: false # Core footprint_margin_scale: 1.0 diff --git a/autoware_launch/config/planning/mission_planning/mission_planner/mission_planner.param.yaml b/autoware_launch/config/planning/mission_planning/mission_planner/mission_planner.param.yaml new file mode 100644 index 0000000000..a801eca35c --- /dev/null +++ b/autoware_launch/config/planning/mission_planning/mission_planner/mission_planner.param.yaml @@ -0,0 +1,8 @@ +/**: + ros__parameters: + map_frame: map + arrival_check_angle_deg: 45.0 + arrival_check_distance: 1.0 + arrival_check_duration: 1.0 + goal_angle_threshold_deg: 45.0 + enable_correct_goal_pose: false diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml index 654e291cd2..e3899e3820 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml @@ -10,6 +10,7 @@ obstacle_velocity_thresh_to_start_acc: 3.5 # start adaptive cruise control when the velocity of the forward obstacle exceeds this value [m/s] obstacle_velocity_thresh_to_stop_acc: 3.0 # stop adaptive cruise control when the velocity of the forward obstacle falls below this value [m/s] emergency_stop_acceleration: -4.5 # supposed minimum acceleration (deceleration) in emergency stop [m/ss] + obstacle_emergency_stop_acceleration: -5.0 emergency_stop_idling_time: 0.5 # supposed idling time to start emergency stop [s] min_dist_stop: 6.0 # minimum distance of emergency stop [m] max_standard_acceleration: 1.0 # supposed maximum acceleration in active cruise control [m/ss] @@ -18,6 +19,7 @@ min_dist_standard: 6.0 # minimum distance in active cruise control [m] obstacle_min_standard_acceleration: -2.0 # supposed minimum acceleration of forward obstacle [m/ss] margin_rate_to_change_vel: 0.7 # margin to insert upper velocity [-] + use_time_compensation_to_calc_distance: true # pid parameter for ACC p_coefficient_positive: 0.25 # coefficient P in PID control (used when target dist -current_dist >=0) [-] 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 6924435ebc..141297a2a7 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 @@ -26,7 +26,7 @@ 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] + enable_stop_behind_goal_for_obstacle: True # enable extend trajectory after goal lane for obstacle detection slow_down_planner: diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 52a8503829..8367c2b562 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -105,7 +105,7 @@ - + diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml index 3cd4ba4284..d9f119c241 100644 --- a/autoware_launch/launch/components/tier4_planning_component.launch.xml +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -23,6 +23,9 @@ + + +