diff --git a/autoware_launch/config/control/control_validator/control_validator.param.yaml b/autoware_launch/config/control/control_validator/control_validator.param.yaml new file mode 100644 index 0000000000..9ce677b2c2 --- /dev/null +++ b/autoware_launch/config/control/control_validator/control_validator.param.yaml @@ -0,0 +1,14 @@ +/**: + ros__parameters: + + publish_diag: true # if true, diagnostic msg is published + + # If the number of consecutive invalid predicted_path exceeds this threshold, the Diag will be set to ERROR. + # (For example, threshold = 1 means, even if the predicted_path is invalid, Diag will not be ERROR if + # the next predicted_path is valid.) + diag_error_count_threshold: 0 + + display_on_terminal: true # show error msg on terminal + + thresholds: + max_distance_deviation: 1.0 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 59e25cbc5d..008832b1ca 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 @@ -7,6 +7,7 @@ include_left_lanes: false include_opposite_lanes: false include_conflicting_lanes: false + road_border_departure_checker: false # Core footprint_margin_scale: 1.0 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index f27429ae81..7f2e92419b 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -154,7 +154,8 @@ lateral_execution_threshold: 0.09 # [m] lateral_small_shift_threshold: 0.101 # [m] lateral_avoid_check_threshold: 0.1 # [m] - road_shoulder_safety_margin: 0.3 # [m] + soft_road_shoulder_margin: 0.3 # [m] + hard_road_shoulder_margin: 0.3 # [m] max_right_shift_length: 5.0 max_left_shift_length: 5.0 # avoidance distance parameters 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 f681398717..bb64006656 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 @@ -9,6 +9,7 @@ debug: # flag to publish enable_pub_debug_marker: true # publish debug marker + enable_pub_extra_debug_marker: false # publish extra debug marker # flag to show enable_debug_info: false @@ -77,7 +78,7 @@ # avoidance avoidance: - max_bound_fixing_time: 3.0 # [s] + max_bound_fixing_time: 1.0 # [s] max_longitudinal_margin_for_bound_violation: 1.0 # [m] max_avoidance_cost: 0.5 # [m] avoidance_cost_margin: 0.0 # [m] diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml index 9708456df4..2c5fe6e8f5 100644 --- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml +++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml @@ -19,6 +19,7 @@ autonomous_driving: /autoware/control/autonomous_driving/node_alive_monitoring: default /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default + /autoware/control/autonomous_driving/performance_monitoring/trajectory_deviation: default /autoware/control/control_command_gate/node_alive_monitoring: default /autoware/localization/node_alive_monitoring: default diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml index 7b3169eacd..8b29135048 100644 --- a/autoware_launch/launch/components/tier4_control_component.launch.xml +++ b/autoware_launch/launch/components/tier4_control_component.launch.xml @@ -35,6 +35,7 @@ + diff --git a/autoware_launch/launch/components/tier4_simulator_component.launch.xml b/autoware_launch/launch/components/tier4_simulator_component.launch.xml index bd191f7a56..f243414555 100644 --- a/autoware_launch/launch/components/tier4_simulator_component.launch.xml +++ b/autoware_launch/launch/components/tier4_simulator_component.launch.xml @@ -43,5 +43,6 @@ +