diff --git a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml index 400bc926a1..0bd5f74fd9 100644 --- a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml +++ b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml @@ -19,12 +19,12 @@ qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp) mpc_prediction_horizon: 50 # prediction horizon step mpc_prediction_dt: 0.1 # prediction horizon period [s] - mpc_weight_lat_error: 0.1 # lateral error weight in matrix Q + mpc_weight_lat_error: 1.0 # lateral error weight in matrix Q mpc_weight_heading_error: 0.0 # heading error weight in matrix Q mpc_weight_heading_error_squared_vel: 0.3 # heading error * velocity weight in matrix Q mpc_weight_steering_input: 1.0 # steering error weight in matrix R mpc_weight_steering_input_squared_vel: 0.25 # steering error * velocity weight in matrix R - mpc_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R + mpc_weight_lat_jerk: 0.1 # lateral jerk weight in matrix R mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R mpc_low_curvature_weight_lat_error: 0.1 # lateral error weight in matrix Q in low curvature point diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml index 3e390d855d..6d19b61995 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml @@ -16,5 +16,6 @@ drivable_area_generation: lat_offset_from_obstacle: 0.8 # [m] - time_to_avoid: 5.0 # [s] + time_to_avoid_same_directional_object: 5.0 # [s] + time_to_avoid_opposite_directional_object: 6.0 # [s] max_lat_offset_to_avoid: 0.5 # [m] diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 01a8dfb483..3f4655b782 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -110,6 +110,7 @@ avoidance_cost_margin: 0.0 # [m] avoidance_cost_band_length: 5.0 # [m] avoidance_cost_decrease_rate: 0.05 # decreased cost per point interval + min_drivable_width: 0.2 # [m] The vehicle width and this parameter is guaranteed to keep for collision free constraint. weight: lat_error_weight: 0.0 # weight for lateral error