diff --git a/autoware_launch/config/localization/ndt_scan_matcher/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher/ndt_scan_matcher.param.yaml index 144449ce75..241892e67b 100644 --- a/autoware_launch/config/localization/ndt_scan_matcher/ndt_scan_matcher.param.yaml +++ b/autoware_launch/config/localization/ndt_scan_matcher/ndt_scan_matcher.param.yaml @@ -11,6 +11,12 @@ map_frame: "map" + sensor_points: + # Required distance of input sensor points. [m] + # If the max distance of input sensor points is lower than this value, the scan matching will not be performed. + required_distance: 10.0 + + ndt: # The maximum difference between two consecutive # transformations in order to consider convergence diff --git a/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml index 4c58c066ed..f2be6aeb8b 100644 --- a/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml +++ b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml @@ -11,8 +11,8 @@ max_x: 150.0 min_y: -70.0 max_y: 70.0 - max_z: 2.5 - min_z: -2.5 # recommended 0.0 for non elevation_grid_mode + margin_max_z: 0.0 # to extend the crop box max_z from vehicle_height + margin_min_z: -2.5 # to extend the crop box min_z from ground negative: False common_ground_filter: diff --git a/autoware_launch/config/perception/occupancy_grid_map/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml b/autoware_launch/config/perception/occupancy_grid_map/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml new file mode 100644 index 0000000000..f9a1c4f930 --- /dev/null +++ b/autoware_launch/config/perception/occupancy_grid_map/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml @@ -0,0 +1,53 @@ +# sample grid map fusion parameters for sample sensor kit +/**: + ros__parameters: + # shared parameters + shared_config: + map_frame: "map" + base_link_frame: "base_link" + # center of the grid map + gridmap_origin_frame: "base_link" + + map_resolution: 0.5 # [m] + map_length_x: 150.0 # [m] + map_length_y: 150.0 # [m] + + # each grid map parameters + ogm_creation_config: + height_filter: + use_height_filter: true + min_height: -1.0 + max_height: 2.0 + enable_single_frame_mode: true + # use sensor pointcloud to filter obstacle pointcloud + filter_obstacle_pointcloud_by_raw_pointcloud: true + + grid_map_type: "OccupancyGridMapFixedBlindSpot" + OccupancyGridMapFixedBlindSpot: + distance_margin: 1.0 + OccupancyGridMapProjectiveBlindSpot: + projection_dz_threshold: 0.01 # [m] for avoiding null division + obstacle_separation_threshold: 1.0 # [m] fill the interval between obstacles with unknown for this length + pub_debug_grid: false + + # parameter settings for ogm fusion + fusion_config: + # following parameters are shared: map_frame, base_link_frame, gridmap_origin_frame, map_resolution, map_length + # Setting1: tune ogm creation parameters + raw_pointcloud_topics: # put each sensor's pointcloud topic + - "/sensing/lidar/top/pointcloud" + - "/sensing/lidar/left/pointcloud" + - "/sensing/lidar/right/pointcloud" + fusion_input_ogm_topics: + - "/perception/occupancy_grid_map/top_lidar/map" + - "/perception/occupancy_grid_map/left_lidar/map" + - "/perception/occupancy_grid_map/right_lidar/map" + # reliability of each sensor (0.0 ~ 1.0) only work with "log-odds" and "dempster-shafer" + input_ogm_reliabilities: + - 1.0 + - 0.6 + - 0.6 + + # Setting2: tune ogm fusion parameters + ## choose fusion method from ["overwrite", "log-odds", "dempster-shafer"] + fusion_method: "overwrite" diff --git a/autoware_launch/config/perception/occupancy_grid_map/synchronized_grid_map_fusion_node.param.yaml b/autoware_launch/config/perception/occupancy_grid_map/synchronized_grid_map_fusion_node.param.yaml new file mode 100644 index 0000000000..f8a2dc2fbc --- /dev/null +++ b/autoware_launch/config/perception/occupancy_grid_map/synchronized_grid_map_fusion_node.param.yaml @@ -0,0 +1,20 @@ +/**: + ros__parameters: + # 1. fusion parameters + fusion_input_ogm_topics: ["topic1", "topic2"] + input_ogm_reliabilities: [0.8, 0.2] + fusion_method: "overwrite" # choose from ["overwrite", "log-odds", "dempster-shafer"] + + # 2. synchronization settings + match_threshold_sec: 0.01 # 10ms + timeout_sec: 0.1 # 100ms + input_offset_sec: [0.0, 0.0] # no offset + + # 3. settings for fused fusion map + # remember resolution and map size should be same with input maps + map_frame_: "map" + base_link_frame_: "base_link" + grid_map_origin_frame_: "base_link" + fusion_map_length_x: 100.0 + fusion_map_length_y: 100.0 + fusion_map_resolution: 0.5 diff --git a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml index face8610c7..5680a99713 100644 --- a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml @@ -9,10 +9,6 @@ min_jerk: -1.0 # min jerk [m/sss] max_jerk: 1.0 # max jerk [m/sss] - slow_down: - min_acc: -1.0 # min deceleration [m/ss] - min_jerk: -1.0 # min jerk [m/sss] - # constraints to be observed limit: min_acc: -2.5 # min deceleration limit [m/ss] 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 ac7873a994..619539be0d 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 @@ -29,80 +29,96 @@ execute_num: 1 # [-] moving_speed_threshold: 1.0 # [m/s] moving_time_threshold: 2.0 # [s] + lateral_margin: + soft_margin: 0.3 # [m] + hard_margin: 0.2 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 # [-] envelope_buffer_margin: 0.5 # [m] - avoid_margin_lateral: 0.7 # [m] - safety_buffer_lateral: 0.3 # [m] safety_buffer_longitudinal: 0.0 # [m] use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. truck: execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 2.0 + lateral_margin: + soft_margin: 0.3 # [m] + hard_margin: 0.2 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - avoid_margin_lateral: 0.9 - safety_buffer_lateral: 0.1 safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true bus: execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 2.0 + lateral_margin: + soft_margin: 0.3 # [m] + hard_margin: 0.2 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - avoid_margin_lateral: 0.9 - safety_buffer_lateral: 0.1 safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true trailer: execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 2.0 + lateral_margin: + soft_margin: 0.3 # [m] + hard_margin: 0.2 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - avoid_margin_lateral: 0.9 - safety_buffer_lateral: 0.1 safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true unknown: execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 + lateral_margin: + soft_margin: 0.7 # [m] + hard_margin: -0.2 # [m] + hard_margin_for_parked_vehicle: -0.2 # [m] max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 - avoid_margin_lateral: 0.7 - safety_buffer_lateral: -0.2 safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true bicycle: execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 + lateral_margin: + soft_margin: 0.7 # [m] + hard_margin: 0.5 # [m] + hard_margin_for_parked_vehicle: 0.5 # [m] max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - avoid_margin_lateral: 0.7 - safety_buffer_lateral: 0.5 safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true motorcycle: execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 + lateral_margin: + soft_margin: 0.7 # [m] + hard_margin: 0.3 # [m] + hard_margin_for_parked_vehicle: 0.3 # [m] max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - avoid_margin_lateral: 0.7 - safety_buffer_lateral: 0.3 safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true pedestrian: execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 + lateral_margin: + soft_margin: 0.7 # [m] + hard_margin: 0.5 # [m] + hard_margin_for_parked_vehicle: 0.5 # [m] max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - avoid_margin_lateral: 0.7 - safety_buffer_lateral: 0.5 safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true lower_distance_for_polygon_expansion: 30.0 # [m] @@ -138,10 +154,12 @@ backward_distance: 10.0 # [m] # params for avoidance of vehicle type objects that are ambiguous as to whether they are parked. - force_avoidance: + avoidance_for_ambiguous_vehicle: enable: true # [-] - time_threshold: 3.0 # [s] - distance_threshold: 1.0 # [m] + closest_distance_to_wait_and_see: 10.0 # [m] + condition: + time_threshold: 3.0 # [s] + distance_threshold: 1.0 # [m] ignore_area: traffic_light: front_distance: 100.0 # [m] @@ -176,7 +194,7 @@ check_all_predicted_path: false # [-] safety_check_backward_distance: 100.0 # [m] hysteresis_factor_expand_rate: 1.5 # [-] - hysteresis_factor_safe_count: 10 # [-] + hysteresis_factor_safe_count: 3 # [-] # predicted path parameters min_velocity: 1.38 # [m/s] max_velocity: 50.0 # [m/s] @@ -192,7 +210,7 @@ rear_vehicle_safety_time_margin: 1.0 # [s] lateral_distance_max_threshold: 2.0 # [m] longitudinal_distance_min_threshold: 3.0 # [m] - longitudinal_velocity_delta_time: 0.8 # [s] + longitudinal_velocity_delta_time: 0.0 # [s] # For avoidance maneuver avoidance: diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lane_change/avoidance_by_lane_change.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lane_change/avoidance_by_lane_change.param.yaml index 74c6112c0e..ce0ba25700 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lane_change/avoidance_by_lane_change.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lane_change/avoidance_by_lane_change.param.yaml @@ -12,64 +12,80 @@ moving_time_threshold: 1.0 # [s] max_expand_ratio: 0.0 # [-] envelope_buffer_margin: 0.3 # [m] - avoid_margin_lateral: 0.0 # [m] - safety_buffer_lateral: 0.0 # [m] + lateral_margin: + soft_margin: 0.0 # [m] + hard_margin: 0.0 # [m] + hard_margin_for_parked_vehicle: 0.0 # [m] truck: execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 - avoid_margin_lateral: 0.0 - safety_buffer_lateral: 0.0 + lateral_margin: + soft_margin: 0.0 # [m] + hard_margin: 0.0 # [m] + hard_margin_for_parked_vehicle: 0.0 # [m] bus: execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 - avoid_margin_lateral: 0.0 - safety_buffer_lateral: 0.0 + lateral_margin: + soft_margin: 0.0 # [m] + hard_margin: 0.0 # [m] + hard_margin_for_parked_vehicle: 0.0 # [m] trailer: execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 - avoid_margin_lateral: 0.0 - safety_buffer_lateral: 0.0 + lateral_margin: + soft_margin: 0.0 # [m] + hard_margin: 0.0 # [m] + hard_margin_for_parked_vehicle: 0.0 # [m] unknown: execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 - avoid_margin_lateral: 0.0 - safety_buffer_lateral: 0.0 + lateral_margin: + soft_margin: 0.0 # [m] + hard_margin: 0.0 # [m] + hard_margin_for_parked_vehicle: 0.0 # [m] bicycle: execute_num: 2 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 - avoid_margin_lateral: 0.0 - safety_buffer_lateral: 1.0 + lateral_margin: + soft_margin: 0.0 # [m] + hard_margin: 1.0 # [m] + hard_margin_for_parked_vehicle: 1.0 # [m] motorcycle: execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 - avoid_margin_lateral: 0.0 - safety_buffer_lateral: 1.0 + lateral_margin: + soft_margin: 0.0 # [m] + hard_margin: 1.0 # [m] + hard_margin_for_parked_vehicle: 1.0 # [m] pedestrian: execute_num: 2 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 - avoid_margin_lateral: 0.0 - safety_buffer_lateral: 1.0 + lateral_margin: + soft_margin: 0.0 # [m] + hard_margin: 1.0 # [m] + hard_margin_for_parked_vehicle: 1.0 # [m] lower_distance_for_polygon_expansion: 0.0 # [m] upper_distance_for_polygon_expansion: 1.0 # [m] 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 2d50f39d72..41e4f90bbc 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,7 @@ th_stopped_time: 1.0 collision_check_margins: [2.0, 1.0, 0.5, 0.1] collision_check_margin_from_front_object: 5.0 + extra_width_margin_for_rear_obstacle: 0.5 th_moving_object_velocity: 1.0 object_types_to_check_for_path_generation: check_car: true diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml index 87140169b4..ac18c935dd 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml @@ -75,7 +75,7 @@ occluded_object_velocity: 1.0 # [m/s] assumed velocity of objects that may come out of the occluded space slow_down_velocity: 1.0 # [m/s] time_buffer: 0.5 # [s] consecutive time with/without an occlusion to add/remove the slowdown - min_size: 0.5 # [m] minimum size of an occlusion (square side size) + min_size: 1.0 # [m] minimum size of an occlusion (square side size) free_space_max: 43 # [-] maximum value of a free space cell in the occupancy grid occupied_min: 58 # [-] minimum value of an occupied cell in the occupancy grid ignore_with_red_traffic_light: true # [-] if true, occlusions at crosswalks with traffic lights are ignored diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml index 14483093e8..c18de5bd53 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml @@ -8,3 +8,4 @@ hysteresis: 1.0 # [m] once a collision has been detected, this hysteresis is used on the collision detection decision_duration_buffer : 1.0 # [s] duration between no collision being detected and the stop decision being cancelled minimum_object_distance_from_ego_path: 1.0 # [m] minimum distance between the footprints of ego and an object to consider for collision + ignore_unavoidable_collisions : true # if true, ignore collisions that cannot be avoided by stopping (assuming the obstacle continues going straight) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml index b55c3b21de..689775ab91 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml @@ -18,6 +18,7 @@ # if false, assume the object moves at constant velocity along *all* lanelets it currently is located in. predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane + cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights overlap: minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered 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 f922148089..77be0b60c2 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 @@ -16,6 +16,8 @@ terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m] hold_stop_velocity_threshold: 0.01 # The maximum ego velocity to hold stopping [m/s] hold_stop_distance_threshold: 0.3 # The ego keeps stopping if the distance to stop changes within the threshold [m] + slow_down_min_acc: -1.0 # slow down min deceleration [m/ss] + slow_down_min_jerk: -1.0 # slow down min jerk [m/sss] nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index @@ -96,7 +98,7 @@ ego_obstacle_overlap_time_threshold : 2.0 # time threshold to decide cut-in obstacle for cruise or stop [s] max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego yield: - enable_yield: false + enable_yield: true lat_distance_threshold: 5.0 # lateral margin between obstacle in neighbor lanes and trajectory band with ego's width for yielding max_lat_dist_between_obstacles: 2.5 # lateral margin between moving obstacle in neighbor lanes and stopped obstacle in front of it max_obstacles_collision_time: 10.0 # how far the blocking obstacle diff --git a/autoware_launch/config/system/component_state_monitor/topics.yaml b/autoware_launch/config/system/component_state_monitor/topics.yaml index f8c6f9685f..f056892849 100644 --- a/autoware_launch/config/system/component_state_monitor/topics.yaml +++ b/autoware_launch/config/system/component_state_monitor/topics.yaml @@ -59,7 +59,7 @@ topic_type: geometry_msgs/msg/PoseWithCovarianceStamped best_effort: false transient_local: false - warn_rate: 5.0 + warn_rate: 2.0 error_rate: 1.0 timeout: 1.0 diff --git a/autoware_launch/config/system/duplicated_node_checker/duplicated_node_checker.param.yaml b/autoware_launch/config/system/duplicated_node_checker/duplicated_node_checker.param.yaml index 54b4f691b6..96dce7eb36 100644 --- a/autoware_launch/config/system/duplicated_node_checker/duplicated_node_checker.param.yaml +++ b/autoware_launch/config/system/duplicated_node_checker/duplicated_node_checker.param.yaml @@ -1,4 +1,4 @@ /**: ros__parameters: update_rate: 10.0 - add_duplicated_node_names_to_msg: false # if true, duplicated node names are added to msg + add_duplicated_node_names_to_msg: true # if true, duplicated node names are added to msg diff --git a/autoware_launch/config/system/mrm_handler/mrm_handler.param.yaml b/autoware_launch/config/system/mrm_handler/mrm_handler.param.yaml new file mode 100644 index 0000000000..e82ee36a78 --- /dev/null +++ b/autoware_launch/config/system/mrm_handler/mrm_handler.param.yaml @@ -0,0 +1,17 @@ +# Default configuration for mrm handler +--- +/**: + ros__parameters: + update_rate: 10 + timeout_operation_mode_availability: 0.5 + timeout_call_mrm_behavior: 0.01 + timeout_cancel_mrm_behavior: 0.01 + use_emergency_holding: false + timeout_emergency_recovery: 5.0 + use_parking_after_stopped: false + use_pull_over: false + use_comfortable_stop: false + + # setting whether to turn hazard lamp on for each situation + turning_hazard_on: + emergency: true diff --git a/autoware_launch/config/vehicle/raw_vehicle_cmd_converter/raw_vehicle_cmd_converter.param.yaml b/autoware_launch/config/vehicle/raw_vehicle_cmd_converter/raw_vehicle_cmd_converter.param.yaml index f6676bdbe7..aa76152e57 100644 --- a/autoware_launch/config/vehicle/raw_vehicle_cmd_converter/raw_vehicle_cmd_converter.param.yaml +++ b/autoware_launch/config/vehicle/raw_vehicle_cmd_converter/raw_vehicle_cmd_converter.param.yaml @@ -1,5 +1,8 @@ /**: ros__parameters: + csv_path_accel_map: $(find-pkg-share raw_vehicle_cmd_converter)/data/default/accel_map.csv + csv_path_brake_map: $(find-pkg-share raw_vehicle_cmd_converter)/data/default/brake_map.csv + csv_path_steer_map: $(find-pkg-share raw_vehicle_cmd_converter)/data/default/steer_map.csv convert_accel_cmd: true convert_brake_cmd: true convert_steer_cmd: false diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml index 3b0f8eca46..8418afabdf 100644 --- a/autoware_launch/launch/components/tier4_perception_component.launch.xml +++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml @@ -1,6 +1,10 @@ - + + + + diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 9b998dc29b..8b305e3e46 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -2374,6 +2374,19 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: false + - Class: rviz_default_plugins/Marker + Enabled: false + Name: Stop Reason + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /control/trajectory_follower/longitudinal/stop_reason + Value: false - Class: rviz_default_plugins/MarkerArray Enabled: false Name: Debug/MPC