diff --git a/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml index 92844c61f6..191e894622 100644 --- a/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml +++ b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml @@ -15,6 +15,8 @@ nominal: vel_lim: 25.0 reference_speed_points: [20.0, 30.0] + steer_lim: [1.0, 0.8] + steer_rate_lim: [1.0, 0.8] lon_acc_lim: [5.0, 4.0] lon_jerk_lim: [5.0, 4.0] lat_acc_lim: [5.0, 4.0] @@ -23,6 +25,8 @@ on_transition: vel_lim: 50.0 reference_speed_points: [20.0, 30.0] + steer_lim: [1.0, 0.8] + steer_rate_lim: [1.0, 0.8] lon_acc_lim: [1.0, 0.9] lon_jerk_lim: [0.5, 0.4] lat_acc_lim: [2.0, 1.8] diff --git a/autoware_launch/config/localization/ekf_localizer.param.yaml b/autoware_launch/config/localization/ekf_localizer.param.yaml index 4d3f5b9643..667217d259 100644 --- a/autoware_launch/config/localization/ekf_localizer.param.yaml +++ b/autoware_launch/config/localization/ekf_localizer.param.yaml @@ -21,3 +21,12 @@ proc_stddev_yaw_c: 0.005 proc_stddev_vx_c: 10.0 proc_stddev_wz_c: 5.0 + + # for diagnostics + pose_no_update_count_threshold_warn: 50 + pose_no_update_count_threshold_error: 250 + twist_no_update_count_threshold_warn: 50 + twist_no_update_count_threshold_error: 250 + + # for velocity measurement limitation (Set 0.0 if you want to ignore) + threshold_observable_velocity_mps: 0.0 # [m/s] diff --git a/autoware_launch/config/localization/localization_error_monitor.param.yaml b/autoware_launch/config/localization/localization_error_monitor.param.yaml index 026daf0532..2aa28014ea 100644 --- a/autoware_launch/config/localization/localization_error_monitor.param.yaml +++ b/autoware_launch/config/localization/localization_error_monitor.param.yaml @@ -4,4 +4,4 @@ error_ellipse_size: 1.0 warn_ellipse_size: 0.8 error_ellipse_size_lateral_direction: 0.3 - warn_ellipse_size_lateral_direction: 0.2 + warn_ellipse_size_lateral_direction: 0.25 diff --git a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml index 3a99927b41..4a22059bda 100644 --- a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml +++ b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml @@ -6,6 +6,9 @@ # Vehicle reference frame base_frame: "base_link" + # NDT reference frame + ndt_base_frame: "ndt_base_link" + # Subscriber queue size input_sensor_points_queue_size: 1 @@ -46,10 +49,6 @@ # Tolerance of distance difference between two initial poses used for linear interpolation. [m] initial_pose_distance_tolerance_m: 10.0 - # neighborhood search method - # 0=KDTREE, 1=DIRECT26, 2=DIRECT7, 3=DIRECT1 - neighborhood_search_method: 0 - # Number of threads used for parallel computing num_threads: 4 @@ -80,8 +79,12 @@ # Radius of input LiDAR range (used for diagnostics of dynamic map loading) lidar_radius: 100.0 + # cspell: ignore degrounded # A flag for using scan matching score based on de-grounded LiDAR scan estimate_scores_for_degrounded_scan: false # If lidar_point.z - base_link.z <= this threshold , the point will be removed z_margin_for_ground_removal: 0.8 + + # The execution time which means probably NDT cannot matches scans properly + critical_upper_bound_exe_time_ms: 100 # [ms] diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml deleted file mode 100644 index 3dd303464a..0000000000 --- a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml +++ /dev/null @@ -1,20 +0,0 @@ -/**: - ros__parameters: - - # distance threshold for compare compare - distance_threshold: 0.5 - - # publish voxelized map pointcloud for debug - publish_debug_pcd: False - - # use dynamic map loading - use_dynamic_map_loading: True - - # time interval to check dynamic map loading - timer_interval_ms: 100 - - # distance threshold for dynamic map update - map_update_distance_threshold: 10.0 - - # radius map for dynamic map loading - map_loader_radius: 150.0 diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml deleted file mode 100644 index 1962fba1f3..0000000000 --- a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml +++ /dev/null @@ -1,8 +0,0 @@ -/**: - ros__parameters: - input_frame: base_link - output_frame: base_link - voxel_size_x: 0.3 - voxel_size_y: 0.3 - voxel_size_z: 100.0 - voxel_points_threshold: 3 diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml deleted file mode 100644 index 3ff32bfbb7..0000000000 --- a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml +++ /dev/null @@ -1,7 +0,0 @@ -/**: - ros__parameters: - input_frame: base_link - output_frame: base_link - voxel_size_x: 0.15 - voxel_size_y: 0.15 - voxel_size_z: 0.15 diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml index 2f3de2b789..26b027f007 100644 --- a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml @@ -7,9 +7,11 @@ max_cluster_size: 3000 use_height: false input_frame: "base_link" - max_x: 70.0 - min_x: -70.0 - max_y: 70.0 - min_y: -70.0 - max_z: 4.5 - min_z: -4.5 + + # low height crop box filter param + max_x: 200.0 + min_x: -200.0 + max_y: 200.0 + min_y: -200.0 + max_z: 2.0 + min_z: -10.0 diff --git a/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml new file mode 100644 index 0000000000..62051e1c5e --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + filter_target_label: + UNKNOWN : true + CAR : true + TRUCK : true + BUS : true + TRAILER : true + MOTORCYCLE : true + BICYCLE : true + PEDESTRIAN : true diff --git a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml index 0423217582..62b3074c15 100644 --- a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml @@ -1,7 +1,5 @@ /**: ros__parameters: - # use downsample filter before compare map - use_down_sample_filter: False # voxel size for downsample filter down_sample_voxel_size: 0.1 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 index 98c28344ea..9b7dcffbc6 100644 --- 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 @@ -9,3 +9,4 @@ reroute_time_threshold: 10.0 minimum_reroute_length: 30.0 consider_no_drivable_lanes: false # This flag is for considering no_drivable_lanes in planning or not. + check_footprint_inside_lanes: true diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index 868b1bd15c..235c76a5c1 100644 --- a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -7,12 +7,21 @@ # external velocity limit parameter margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m] - # curve parameters + # -- curve parameters -- + # common parameters + curvature_calculation_distance: 5.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m] + # lateral acceleration limit parameters + enable_lateral_acc_limit: true # To toggle the lateral acc filter on and off. You can switch it dynamically at runtime. max_lateral_accel: 1.0 # max lateral acceleration limit [m/ss] min_curve_velocity: 2.74 # min velocity at lateral acceleration limit and steering angle rate limit [m/s] decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss] + # steering angle rate limit parameters + enable_steering_rate_limit: true # To toggle the steer rate filter on and off. You can switch it dynamically at runtime. + max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s] + resample_ds: 0.1 # distance between trajectory points [m] + curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m] # engage & replan parameters replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s] @@ -48,12 +57,6 @@ post_sparse_resample_dt: 0.1 # resample time interval for sparse sampling [s] post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m] - # steering angle rate limit parameters - max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s] - resample_ds: 0.1 # distance between trajectory points [m] - curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m] - curvature_calculation_distance: 1.0 # distance of points while curvature is calculating [m] - # system over_stop_velocity_warn_thr: 1.389 # used to check if the optimization exceeds the input velocity on the stop point diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml index 1bfe689c55..e1108d56c9 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml @@ -5,10 +5,14 @@ th_arrived_distance: 1.0 th_stopped_velocity: 0.01 th_stopped_time: 2.0 # It must be greater than the state_machine's. + center_line_path_interval: 1.0 # goal search goal_search: - search_priority: "efficient_path" # "efficient_path" or "close_goal" + goal_priority: "minimum_weighted_distance" # "minimum_weighted_distance" or "minimum_longitudinal_distance" + minimum_weighted_distance: + lateral_weight: 40.0 + path_priority: "efficient_path" # "efficient_path" or "close_goal" parking_policy: "left_side" # "left_side" or "right_side" forward_goal_search_length: 20.0 backward_goal_search_length: 20.0 @@ -21,8 +25,9 @@ # occupancy grid map occupancy_grid: - use_occupancy_grid: true - use_occupancy_grid_for_longitudinal_margin: false + use_occupancy_grid_for_goal_search: true + use_occupancy_grid_for_goal_longitudinal_margin: false + use_occupancy_grid_for_path_collision_check: false occupancy_grid_collision_check_margin: 0.0 theta_size: 360 obstacle_threshold: 60 @@ -32,6 +37,7 @@ use_object_recognition: true object_recognition_collision_check_margin: 0.6 # this should be larger than `surround_check_distance` of surround_obstacle_checker object_recognition_collision_check_max_extra_stopping_margin: 1.0 + th_moving_object_velocity: 1.0 # pull over pull_over: @@ -110,12 +116,13 @@ path_safety_check: # EgoPredictedPath ego_predicted_path: + min_velocity: 0.0 acceleration: 1.0 - time_horizon: 10.0 + max_velocity: 1.0 + time_horizon_for_front_object: 10.0 + time_horizon_for_rear_object: 10.0 time_resolution: 0.5 - min_slow_speed: 0.0 delay_until_departure: 1.0 - target_velocity: 1.0 # For target object filtering target_filtering: safety_check_time_horizon: 5.0 @@ -123,7 +130,7 @@ # detection range object_check_forward_distance: 10.0 object_check_backward_distance: 100.0 - ignore_object_velocity_threshold: 0.0 + ignore_object_velocity_threshold: 1.0 # ObjectTypesToCheck object_types_to_check: check_car: true @@ -150,7 +157,7 @@ # For safety check safety_check_params: # safety check configuration - enable_safety_check: true + enable_safety_check: false # Don't set to true if auto_mode is enabled # collision check parameters check_all_predicted_path: true publish_debug_marker: false @@ -160,6 +167,8 @@ lateral_distance_max_threshold: 1.0 longitudinal_distance_min_threshold: 1.0 longitudinal_velocity_delta_time: 1.0 + # hysteresis factor to expand/shrink polygon with the value + hysteresis_factor_expand_rate: 1.0 # temporary backward_path_length: 30.0 forward_path_length: 100.0 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index 372ed9041c..1accb1f709 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -62,6 +62,16 @@ check_objects_on_other_lanes: true use_all_predicted_path: true + # lane change regulations + regulation: + crosswalk: false + intersection: false + + # ego vehicle stuck detection + stuck_detection: + velocity: 0.1 # [m/s] + stop_time: 3.0 # [s] + # lane change cancel cancel: enable_on_prepare_phase: true diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml index a3c0194d03..ff4b486ef9 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml @@ -9,7 +9,7 @@ enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: true keep_last: false - priority: 7 + priority: 6 max_module_size: 1 external_request_lane_change_right: @@ -18,7 +18,7 @@ enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: true keep_last: false - priority: 7 + priority: 6 max_module_size: 1 lane_change_left: @@ -27,7 +27,7 @@ enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: true keep_last: false - priority: 6 + priority: 5 max_module_size: 1 lane_change_right: @@ -36,7 +36,7 @@ enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: true keep_last: false - priority: 6 + priority: 5 max_module_size: 1 start_planner: @@ -72,7 +72,7 @@ enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: false keep_last: false - priority: 5 + priority: 4 max_module_size: 1 avoidance_by_lc: @@ -81,7 +81,7 @@ enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false keep_last: false - priority: 4 + priority: 3 max_module_size: 1 dynamic_avoidance: @@ -89,6 +89,6 @@ enable_rtc: true enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: true - keep_last: false - priority: 3 + keep_last: true + priority: 7 max_module_size: 1 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml index b62262423f..352a0bf350 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml @@ -7,6 +7,8 @@ collision_check_margin: 1.0 collision_check_distance_from_end: 1.0 th_moving_object_velocity: 1.0 + th_distance_to_middle_of_the_road: 0.1 + center_line_path_interval: 1.0 # shift pull out enable_shift_pull_out: true check_shift_path_lane_departure: false @@ -79,12 +81,13 @@ path_safety_check: # EgoPredictedPath ego_predicted_path: + min_velocity: 0.0 acceleration: 1.0 - time_horizon: 10.0 + max_velocity: 1.0 + time_horizon_for_front_object: 10.0 + time_horizon_for_rear_object: 10.0 time_resolution: 0.5 - min_slow_speed: 0.0 delay_until_departure: 1.0 - target_velocity: 1.0 # For target object filtering target_filtering: safety_check_time_horizon: 5.0 @@ -92,7 +95,7 @@ # detection range object_check_forward_distance: 10.0 object_check_backward_distance: 100.0 - ignore_object_velocity_threshold: 0.0 + ignore_object_velocity_threshold: 1.0 # ObjectTypesToCheck object_types_to_check: check_car: true @@ -119,7 +122,7 @@ # For safety check safety_check_params: # safety check configuration - enable_safety_check: true + enable_safety_check: false # Don't set to true if auto_mode is enabled # collision check parameters check_all_predicted_path: true publish_debug_marker: false @@ -129,6 +132,8 @@ lateral_distance_max_threshold: 1.0 longitudinal_distance_min_threshold: 1.0 longitudinal_velocity_delta_time: 1.0 + # hysteresis factor to expand/shrink polygon + hysteresis_factor_expand_rate: 1.0 # temporary backward_path_length: 30.0 forward_path_length: 100.0 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index 00df2e2ced..a932254140 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -24,12 +24,15 @@ state_transit_margin_time: 1.0 min_predicted_path_confidence: 0.05 minimum_ego_predicted_velocity: 1.388 # [m/s] - normal: - collision_start_margin_time: 4.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object - collision_end_margin_time: 6.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object - relaxed: + fully_prioritized: collision_start_margin_time: 2.0 collision_end_margin_time: 0.0 + partially_prioritized: + collision_start_margin_time: 2.0 + collision_end_margin_time: 2.0 + not_prioritized: + collision_start_margin_time: 4.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object + collision_end_margin_time: 6.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object keep_detection_vel_thr: 0.833 # == 3.0km/h. keep detection if ego is ego.vel < keep_detection_vel_thr occlusion: @@ -48,6 +51,7 @@ possible_object_bbox: [1.5, 2.5] # [m x m] ignore_parked_vehicle_speed_threshold: 0.8333 # == 3.0km/h stop_release_margin_time: 1.5 # [s] + temporal_stop_before_attention_area: false enable_rtc: intersection: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval @@ -56,3 +60,4 @@ merge_from_private: stop_line_margin: 3.0 stop_duration_sec: 1.0 + stop_distance_threshold: 1.0 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index aadd0ccd02..cb4d6a68c5 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -106,6 +106,13 @@ successive_num_to_entry_slow_down_condition: 5 successive_num_to_exit_slow_down_condition: 5 + # consider the current ego pose (it is not the nearest pose on the reference trajectory) + # Both the lateral error and the yaw error are assumed to decrease to zero by the time duration "time_to_convergence" + # The both errors decrease with constant rates against the time. + consider_current_pose: + enable_to_consider_current_pose: true + time_to_convergence: 1.5 #[s] + cruise: pid_based_planner: use_velocity_limit_based_planner: true diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml new file mode 100644 index 0000000000..2f98f9d0e2 --- /dev/null +++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml @@ -0,0 +1,52 @@ +# Description: +# name: diag name +# sf_at: diag level where it becomes Safe Fault +# lf_at: diag level where it becomes Latent Fault +# spf_at: diag level where it becomes Single Point Fault +# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. +# +# Note: +# empty-value for sf_at, lf_at and spf_at is "none" +# default values are: +# sf_at: "none" +# lf_at: "warn" +# spf_at: "error" +# auto_recovery: "true" +--- +/**: + ros__parameters: + required_modules: + autonomous_driving: + /autoware/control/autonomous_driving/node_alive_monitoring: default + /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default + /autoware/control/control_command_gate/node_alive_monitoring: default + + /autoware/localization/node_alive_monitoring: default + /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } + /autoware/localization/performance_monitoring/localization_accuracy: { sf_at: "warn", lf_at: "none", spf_at: "none" } + + /autoware/map/node_alive_monitoring: default + + /autoware/perception/node_alive_monitoring: default + + /autoware/planning/node_alive_monitoring: default + /autoware/planning/performance_monitoring/trajectory_validation: default + + # /autoware/sensing/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } + # /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" } + + /autoware/vehicle/node_alive_monitoring: default + + external_control: + /autoware/control/control_command_gate/node_alive_monitoring: default + /autoware/control/external_control/external_command_selector/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } + + /autoware/vehicle/node_alive_monitoring: default diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 1a4fbb70f4..5d98c9388f 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -6,6 +6,7 @@ + @@ -32,6 +33,7 @@ + @@ -89,7 +91,9 @@ - + + + diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml index cf5b2dd98c..342396934c 100644 --- a/autoware_launch/launch/components/tier4_perception_component.launch.xml +++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml @@ -8,6 +8,7 @@ default="obstacle_pointcloud" description="options: obstacle_pointcloud, occupancy_grid (occupancy_grid_map_method must be laserscan_based_occupancy_grid_map)" /> + @@ -19,18 +20,14 @@ + - - + - + - + diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml index 3cfc6d8541..1bd74ccbbf 100644 --- a/autoware_launch/launch/components/tier4_system_component.launch.xml +++ b/autoware_launch/launch/components/tier4_system_component.launch.xml @@ -1,5 +1,7 @@ + + @@ -10,7 +12,7 @@ - + diff --git a/autoware_launch/launch/e2e_simulator.launch.xml b/autoware_launch/launch/e2e_simulator.launch.xml index 9ce8a421e9..fe8d1de1d8 100644 --- a/autoware_launch/launch/e2e_simulator.launch.xml +++ b/autoware_launch/launch/e2e_simulator.launch.xml @@ -4,6 +4,7 @@ + @@ -26,6 +27,11 @@ + @@ -36,6 +42,7 @@ + @@ -54,6 +61,7 @@ + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 6621c15ea3..7eb13135d3 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -5,6 +5,7 @@ + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 0a97454854..fdc86ebba7 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -4,6 +4,7 @@ + @@ -37,6 +38,7 @@ + diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 0013fc36ca..00e924da39 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -319,6 +319,22 @@ Visualization Manager: Value: true Enabled: true Name: Vehicle + - Class: rviz_plugins/MrmSummaryOverlayDisplay + Enabled: false + Font Size: 10 + Left: 512 + Max Letter Num: 100 + Name: MRM Summary + Text Color: 25; 255; 240 + Top: 64 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /system/emergency/hazard_status + Value: false + Value height offset: 0 Enabled: true Name: System - Class: rviz_common/Group