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/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 dd76f2c4e5..73e7a578fe 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: 1.5 # start adaptive cruise control when the velocity of the forward obstacle exceeds this value [m/s] obstacle_velocity_thresh_to_stop_acc: 1.0 # stop adaptive cruise control when the velocity of the forward obstacle falls below this value [m/s] emergency_stop_acceleration: -5.0 # 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: 4.0 # minimum distance of emergency stop [m] max_standard_acceleration: 0.5 # supposed maximum acceleration in active cruise control [m/ss] @@ -18,6 +19,7 @@ min_dist_standard: 4.0 # minimum distance in active cruise control [m] obstacle_min_standard_acceleration: -1.5 # supposed minimum acceleration of forward obstacle [m/ss] margin_rate_to_change_vel: 0.3 # margin to insert upper velocity [-] + use_time_compensation_to_calc_distance: true # pid parameter for ACC p_coefficient_positive: 0.1 # coefficient P in PID control (used when target dist -current_dist >=0) [-]