diff --git a/autoware_launch/config/control/control_validator/control_validator.param.yaml b/autoware_launch/config/control/control_validator/control_validator.param.yaml
index c51cbafba2..ffd259e5e5 100644
--- a/autoware_launch/config/control/control_validator/control_validator.param.yaml
+++ b/autoware_launch/config/control/control_validator/control_validator.param.yaml
@@ -1,8 +1,6 @@
/**:
ros__parameters:
- publish_diag: false # 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.)
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 9998b6aadf..7820c562e8 100644
--- a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml
+++ b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml
@@ -13,7 +13,7 @@
curvature_smoothing_num_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num)
# -- trajectory extending --
- extend_trajectory_for_end_yaw_control: true # flag of trajectory extending for terminal yaw control
+ extend_trajectory_for_end_yaw_control: false # flag of trajectory extending for terminal yaw control
# -- mpc optimization --
qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp)
diff --git a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
index c39088753f..ad6217663f 100644
--- a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
+++ b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
@@ -69,8 +69,9 @@
max_jerk: 2.0
min_jerk: -5.0
- # pitch
- use_trajectory_for_pitch_calculation: false
+ # slope compensation
lpf_pitch_gain: 0.95
+ slope_source: "raw_pitch" # raw_pitch, trajectory_pitch or trajectory_adaptive
+ adaptive_trajectory_velocity_th: 1.0
max_pitch_rad: 0.1
min_pitch_rad: -0.1
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 7ad685217f..54c87f45b6 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
@@ -3,7 +3,7 @@
update_rate: 10.0
system_emergency_heartbeat_timeout: 0.5
use_emergency_handling: false
- check_external_emergency_heartbeat: false
+ check_external_emergency_heartbeat: $(var check_external_emergency_heartbeat)
use_start_request: false
enable_cmd_limit_filter: true
filter_activated_count_threshold: 5
diff --git a/autoware_launch/config/localization/ar_tag_based_localizer.param.yaml b/autoware_launch/config/localization/ar_tag_based_localizer.param.yaml
new file mode 100644
index 0000000000..e8f9016537
--- /dev/null
+++ b/autoware_launch/config/localization/ar_tag_based_localizer.param.yaml
@@ -0,0 +1,40 @@
+/**:
+ ros__parameters:
+ # marker_size
+ marker_size: 0.6
+
+ # target_tag_ids
+ target_tag_ids: ['0','1','2','3','4','5','6']
+
+ # base_covariance
+ # This value is dynamically scaled according to the distance at which AR tags are detected.
+ base_covariance: [0.2, 0.0, 0.0, 0.0, 0.0, 0.0,
+ 0.0, 0.2, 0.0, 0.0, 0.0, 0.0,
+ 0.0, 0.0, 0.2, 0.0, 0.0, 0.0,
+ 0.0, 0.0, 0.0, 0.02, 0.0, 0.0,
+ 0.0, 0.0, 0.0, 0.0, 0.02, 0.0,
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.02]
+
+ # Detect AR-Tags within this range and publish the pose of ego vehicle
+ distance_threshold: 13.0 # [m]
+
+ # consider_orientation
+ consider_orientation: false
+
+ # Detector parameters
+ # See https://github.com/pal-robotics/aruco_ros/blob/7787a6794d30c248bc546d1582e65dd47bc40c12/aruco/include/aruco/markerdetector.h#L106-L126
+ detection_mode: "DM_NORMAL" # select from [DM_NORMAL, DM_FAST, DM_VIDEO_FAST]
+ min_marker_size: 0.02
+
+ # Parameters for comparison with EKF Pose
+ # If the difference between the EKF pose and the current pose is within the range of values set below, the current pose is published.
+ # [How to determine the value]
+ # * ekf_time_tolerance: Since it is abnormal if the data comes too old from EKF, the tentative tolerance value is set at 5 seconds.
+ # This value is assumed to be unaffected even if it is increased or decreased by some amount.
+ # * ekf_position_tolerance: Since it is possible that multiple AR tags with the same ID could be placed, the tolerance should be as small as possible.
+ # And if the vehicle is running only on odometry in a section without AR tags,
+ # it is possible that self-position estimation could be off by a few meters.
+ # it should be fixed by AR tag detection, so tolerance should not be smaller than 10 meters.
+ # Therefore, the tolerance is set at 10 meters.
+ ekf_time_tolerance: 5.0 # [s]
+ ekf_position_tolerance: 10.0 # [m]
diff --git a/autoware_launch/config/localization/ekf_localizer.param.yaml b/autoware_launch/config/localization/ekf_localizer.param.yaml
index ebdf2828fc..4cc71e0904 100644
--- a/autoware_launch/config/localization/ekf_localizer.param.yaml
+++ b/autoware_launch/config/localization/ekf_localizer.param.yaml
@@ -1,37 +1,46 @@
/**:
ros__parameters:
- show_debug_info: false
- enable_yaw_bias_estimation: true
- predict_frequency: 50.0
- tf_rate: 50.0
- publish_tf: true
- extend_state_step: 50
+ node:
+ show_debug_info: false
+ enable_yaw_bias_estimation: true
+ predict_frequency: 50.0
+ tf_rate: 50.0
+ publish_tf: true
+ extend_state_step: 50
- # for Pose measurement
- pose_additional_delay: 0.0
- pose_measure_uncertainty_time: 0.01
- pose_smoothing_steps: 5
- pose_gate_dist: 10000.0
+ pose_measurement:
+ # for Pose measurement
+ pose_additional_delay: 0.0
+ pose_measure_uncertainty_time: 0.01
+ pose_smoothing_steps: 5
+ pose_gate_dist: 10000.0
- # for twist measurement
- twist_additional_delay: 0.0
- twist_smoothing_steps: 2
- twist_gate_dist: 10000.0
+ twist_measurement:
+ # for twist measurement
+ twist_additional_delay: 0.0
+ twist_smoothing_steps: 2
+ twist_gate_dist: 10000.0
- # for process model
- proc_stddev_yaw_c: 0.005
- proc_stddev_vx_c: 10.0
- proc_stddev_wz_c: 5.0
+ process_noise:
+ # for process model
+ proc_stddev_yaw_c: 0.005
+ proc_stddev_vx_c: 10.0
+ proc_stddev_wz_c: 5.0
- #Simple1DFilter parameters
- z_filter_proc_dev: 1.0
- roll_filter_proc_dev: 0.01
- pitch_filter_proc_dev: 0.01
- # for diagnostics
- pose_no_update_count_threshold_warn: 50
- pose_no_update_count_threshold_error: 100
- twist_no_update_count_threshold_warn: 50
- twist_no_update_count_threshold_error: 100
+ simple_1d_filter_parameters:
+ #Simple1DFilter parameters
+ z_filter_proc_dev: 1.0
+ roll_filter_proc_dev: 0.01
+ pitch_filter_proc_dev: 0.01
- # for velocity measurement limitation (Set 0.0 if you want to ignore)
- threshold_observable_velocity_mps: 0.0 # [m/s]
+ diagnostics:
+ # for diagnostics
+ pose_no_update_count_threshold_warn: 50
+ pose_no_update_count_threshold_error: 100
+ twist_no_update_count_threshold_warn: 50
+ twist_no_update_count_threshold_error: 100
+
+ misc:
+ # for velocity measurement limitation (Set 0.0 if you want to ignore)
+ threshold_observable_velocity_mps: 0.0 # [m/s]
+ pose_frame_id: "map"
diff --git a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher/ndt_scan_matcher.param.yaml
similarity index 100%
rename from autoware_launch/config/localization/ndt_scan_matcher.param.yaml
rename to autoware_launch/config/localization/ndt_scan_matcher/ndt_scan_matcher.param.yaml
diff --git a/autoware_launch/config/localization/crop_box_filter_measurement_range.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher/pointcloud_preprocessor/crop_box_filter_measurement_range.param.yaml
similarity index 100%
rename from autoware_launch/config/localization/crop_box_filter_measurement_range.param.yaml
rename to autoware_launch/config/localization/ndt_scan_matcher/pointcloud_preprocessor/crop_box_filter_measurement_range.param.yaml
diff --git a/autoware_launch/config/localization/random_downsample_filter.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher/pointcloud_preprocessor/random_downsample_filter.param.yaml
similarity index 100%
rename from autoware_launch/config/localization/random_downsample_filter.param.yaml
rename to autoware_launch/config/localization/ndt_scan_matcher/pointcloud_preprocessor/random_downsample_filter.param.yaml
diff --git a/autoware_launch/config/localization/voxel_grid_filter.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher/pointcloud_preprocessor/voxel_grid_filter.param.yaml
similarity index 100%
rename from autoware_launch/config/localization/voxel_grid_filter.param.yaml
rename to autoware_launch/config/localization/ndt_scan_matcher/pointcloud_preprocessor/voxel_grid_filter.param.yaml
diff --git a/autoware_launch/config/localization/pose_initializer.param.yaml b/autoware_launch/config/localization/pose_initializer.param.yaml
index a05cc7c35c..88acbfb526 100644
--- a/autoware_launch/config/localization/pose_initializer.param.yaml
+++ b/autoware_launch/config/localization/pose_initializer.param.yaml
@@ -2,6 +2,11 @@
ros__parameters:
gnss_pose_timeout: 3.0 # [sec]
stop_check_duration: 3.0 # [sec]
+ ekf_enabled: $(var ekf_enabled)
+ gnss_enabled: $(var gnss_enabled)
+ yabloc_enabled: $(var yabloc_enabled)
+ ndt_enabled: $(var ndt_enabled)
+ stop_check_enabled: $(var stop_check_enabled)
# from gnss
gnss_particle_covariance:
diff --git a/autoware_launch/config/map/lanelet2_map_loader.param.yaml b/autoware_launch/config/map/lanelet2_map_loader.param.yaml
index 24d2b0e8ed..b830e038f1 100755
--- a/autoware_launch/config/map/lanelet2_map_loader.param.yaml
+++ b/autoware_launch/config/map/lanelet2_map_loader.param.yaml
@@ -1,3 +1,4 @@
/**:
ros__parameters:
center_line_resolution: 5.0 # [m]
+ lanelet2_map_path: $(var lanelet2_map_path) # The lanelet2 map path
diff --git a/autoware_launch/config/map/map_tf_generator.param.yaml b/autoware_launch/config/map/map_tf_generator.param.yaml
new file mode 100644
index 0000000000..90790808ac
--- /dev/null
+++ b/autoware_launch/config/map/map_tf_generator.param.yaml
@@ -0,0 +1,4 @@
+/**:
+ ros__parameters:
+ map_frame: map
+ viewer_frame: viewer
diff --git a/autoware_launch/config/map/pointcloud_map_loader.param.yaml b/autoware_launch/config/map/pointcloud_map_loader.param.yaml
index b4efbec970..48d10944cb 100644
--- a/autoware_launch/config/map/pointcloud_map_loader.param.yaml
+++ b/autoware_launch/config/map/pointcloud_map_loader.param.yaml
@@ -7,3 +7,5 @@
# only used when downsample_whole_load enabled
leaf_size: 3.0 # downsample leaf size [m]
+ pcd_paths_or_directory: [$(var pointcloud_map_path)] # Path to the pointcloud map file or directory
+ pcd_metadata_path: $(var pointcloud_map_metadata_path) # Path to pointcloud metadata file
diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml
index 0b29a87965..a9c3174846 100644
--- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml
@@ -13,3 +13,14 @@
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
+ score_threshold: 0.35
+ has_twist: false
+ trt_precision: fp16
+ densification_num_past_frames: 1
+ densification_world_frame_id: map
+
+ # weight files
+ encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
+ encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
+ head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
+ head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml
index 8252fde827..474d0e2b69 100644
--- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml
@@ -13,3 +13,14 @@
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
+ score_threshold: 0.35
+ has_twist: false
+ trt_precision: fp16
+ densification_num_past_frames: 1
+ densification_world_frame_id: map
+
+ # weight files
+ encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
+ encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
+ head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
+ head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml
index 21d31f2163..8ccd469786 100755
--- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml
@@ -1,5 +1,11 @@
/**:
ros__parameters:
+ trt_precision: fp16
+ encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
+ encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
+ head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
+ head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
+
model_params:
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"]
diff --git a/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml b/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml
index fdd64174de..f8ad371ab9 100644
--- a/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml
@@ -19,6 +19,12 @@
use_vehicle_acceleration: false # whether to consider current vehicle acceleration when predicting paths or not
speed_limit_multiplier: 1.5 # When using vehicle acceleration. Set vehicle's maximum predicted speed as the legal speed limit in that lanelet times this value
acceleration_exponential_half_life: 2.5 # [s] When using vehicle acceleration. The decaying acceleration model considers that the current vehicle acceleration will be halved after this many seconds
+ crosswalk_with_signal:
+ use_crosswalk_signal: true
+ threshold_velocity_assumed_as_stopping: 0.25 # [m/s] velocity threshold for the module to judge whether the objects is stopped
+ # If the pedestrian does not move for X seconds against green signal, the module judge that the pedestrian has no intention to walk.
+ distance_set_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order, keys of map
+ timeout_set_for_no_intention_to_walk: [1.0, 0.0] # [s] values of map
# parameter for shoulder lane prediction
prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8
diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml
index d2c0841cf3..3a1e9f02c3 100644
--- a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml
@@ -24,3 +24,6 @@
max_distance_from_lane: 5.0 # [m]
max_angle_diff_from_lane: 0.785398 # [rad] (45 deg)
max_lateral_velocity: 7.0 # [m/s]
+
+ # tracking model parameters
+ tracking_config_directory: $(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/radar_object_tracker/tracking/
diff --git a/autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml b/autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml
index 5dc2b62eaa..dfe12ff352 100644
--- a/autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml
+++ b/autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml
@@ -3,3 +3,4 @@
external_time_tolerance: 5.0
perception_time_tolerance: 1.0
external_priority: false
+ enable_signal_matching: false
diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml
index 3512d722ec..69328a9b79 100644
--- a/autoware_launch/config/planning/preset/default_preset.yaml
+++ b/autoware_launch/config/planning/preset/default_preset.yaml
@@ -9,6 +9,9 @@ launch:
- arg:
name: launch_dynamic_avoidance_module
default: "false"
+ - arg:
+ name: launch_sampling_planner_module
+ default: "false" # Warning, experimental module, use only in simulations
- arg:
name: launch_lane_change_right_module
default: "true"
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 03958fda9a..face8610c7 100644
--- a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml
@@ -1,5 +1,7 @@
/**:
ros__parameters:
+ max_vel: 11.1 # max velocity limit [m/s]
+
# constraints param for normal driving
normal:
min_acc: -1.0 # min deceleration [m/ss]
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 235c76a5c1..ff97ae8dfb 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
@@ -1,7 +1,6 @@
/**:
ros__parameters:
# motion state constraints
- max_velocity: 20.0 # max velocity limit [m/s]
stop_decel: 0.0 # deceleration at a stop point[m/ss]
# external velocity limit parameter
@@ -9,24 +8,24 @@
# -- 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]
+ curvature_calculation_distance: 2.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]
+ min_curve_velocity: 2.0 # 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]
+ max_steering_angle_rate: 11.5 # 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]
engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed)
- engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement)
+ engage_acceleration: 0.5 # engage acceleration [m/ss] (use this acceleration when engagement)
engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity.
stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m]
diff --git a/autoware_launch/config/planning/scenario_planning/common/planning_validator/planning_validator.param.yaml b/autoware_launch/config/planning/scenario_planning/common/planning_validator/planning_validator.param.yaml
index 658a968906..da337d70b1 100644
--- a/autoware_launch/config/planning/scenario_planning/common/planning_validator/planning_validator.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/common/planning_validator/planning_validator.param.yaml
@@ -26,3 +26,14 @@
steering_rate: 10.0
velocity_deviation: 100.0
distance_deviation: 100.0
+ longitudinal_distance_deviation: 1.0
+
+ parameters:
+ # The required trajectory length is calculated as the distance needed
+ # to stop from the current speed at this deceleration.
+ forward_trajectory_length_acceleration: -3.0
+
+ # An error is raised if the required trajectory length is less than this distance.
+ # Setting it to 0 means an error will occur if even slightly exceeding the end of the path,
+ # therefore, a certain margin is necessary.
+ forward_trajectory_length_margin: 2.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 52724cdda0..2ac846ed25 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
@@ -127,7 +127,7 @@
object_check_return_pose_distance: 20.0 # [m]
# filtering parking objects
threshold_distance_object_is_on_center: 1.0 # [m]
- object_check_shiftable_ratio: 0.6 # [-]
+ object_check_shiftable_ratio: 0.8 # [-]
object_check_min_road_shoulder_width: 0.5 # [m]
# lost object compensation
object_last_seen_threshold: 2.0
@@ -187,6 +187,7 @@
time_horizon_for_rear_object: 10.0 # [s]
delay_until_departure: 0.0 # [s]
# rss parameters
+ extended_polygon_policy: "along_path" # [-] select "rectangle" or "along_path"
expected_front_deceleration: -1.0 # [m/ss]
expected_rear_deceleration: -1.0 # [m/ss]
rear_vehicle_reaction_time: 2.0 # [s]
@@ -206,7 +207,7 @@
hard_road_shoulder_margin: 0.3 # [m]
max_right_shift_length: 5.0
max_left_shift_length: 5.0
- max_deviation_from_lane: 0.5 # [m]
+ max_deviation_from_lane: 0.2 # [m]
# avoidance distance parameters
longitudinal:
min_prepare_time: 1.0 # [s]
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 d03efa405f..66542e1bf1 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
@@ -39,6 +39,9 @@
object_recognition_collision_check_max_extra_stopping_margin: 1.0
th_moving_object_velocity: 1.0
detection_bound_offset: 15.0
+ outer_road_detection_offset: 1.0
+ inner_road_detection_offset: 0.0
+
# pull over
pull_over:
@@ -128,7 +131,7 @@
delay_until_departure: 1.0
# For target object filtering
target_filtering:
- safety_check_time_horizon: 5.0
+ safety_check_time_horizon: 10.0
safety_check_time_resolution: 1.0
# detection range
object_check_forward_distance: 100.0
@@ -164,7 +167,6 @@
method: "integral_predicted_polygon"
keep_unsafe_time: 3.0
# collision check parameters
- check_all_predicted_path: true
publish_debug_marker: false
rss_params:
rear_vehicle_reaction_time: 2.0
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/sampling_planner/sampling_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/sampling_planner/sampling_planner.param.yaml
new file mode 100644
index 0000000000..9a6b30c219
--- /dev/null
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/sampling_planner/sampling_planner.param.yaml
@@ -0,0 +1,40 @@
+/**:
+ ros__parameters:
+ common:
+ output_delta_arc_length: 0.5 # [m] delta arc length for output trajectory
+
+ debug:
+ enable_calculation_time_info: false # flag to print calculation times
+ id: 0 # id of the candidate paths for which to print/show details (e.g., footprint in rviz)
+
+ preprocessing:
+ force_zero_initial_deviation: True # if true, initial planning starts from the reference path
+ force_zero_initial_heading: True # if true, initial planning starts with a heading aligned with the reference path
+ smooth_reference_trajectory: False # if true, the reference trajectory is smoothed before being used for planning
+ constraints:
+ hard:
+ max_curvature: 3.0 # [m⁻¹] maximum curvature of a sampled path
+ min_curvature: -3.0 # [m⁻¹] minimum curvature of a sampled path
+ soft:
+ lateral_deviation_weight: 1.0 # cost weight for lateral deviation between the end of a sampled path and the reference path
+ length_weight: 1.0 # cost weight for the length of a sampled path
+ curvature_weight: 2000.0 # cost weight for the curvature of a sampled path
+ weights: [0.5,1.0,20.0]
+ sampling:
+ enable_frenet: True
+ enable_bezier: False
+ resolution: 0.5 # [m] target distance between sampled path points
+ previous_path_reuse_points_nb: 2 # number of points reused from the previously generated path (0:no reuse, 1:replan from end of prev path, 2: end and mid of prev path, etc)
+ target_lengths: [20.0, 40.0] # [m] target lengths of the sampled paths
+ nb_target_lateral_positions: 0 # number of lateral positions to use for sampling (in addition to 0.0 and the current lateral deviation)
+ target_lateral_positions: [-4.5,-2.5, 0.0, 2.5,4.5] # manual values that are only used if nb_target_lateral_positions = 0
+ frenet: # target values for the sampled "lateral deviation over longitudinal position" polynomial
+ target_lateral_velocities: [-0.5, 0.0, 0.5]
+ target_lateral_accelerations: [0.0]
+ # bezier:
+ # nb_k: 3 # number of sampled curvature values
+ # mk_min: 0.0 # minimum curvature value
+ # mk_max: 10.0 # maximum curvature value
+ # nb_t: 5 # number of sampled acceleration values
+ # mt_min: 0.3 # minimum acceleration value
+ # mt_max: 1.7 # maximum acceleration value
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 9853e220bc..8d4fe057b4 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
@@ -82,3 +82,12 @@
keep_last: true
priority: 7
max_module_size: 1
+
+ sampling_planner:
+ enable_module: true
+ enable_rtc: false
+ enable_simultaneous_execution_as_approved_module: false
+ enable_simultaneous_execution_as_candidate_module: false
+ keep_last: false
+ priority: 16
+ 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 154c4b1e0b..2c55e9fad5 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
@@ -6,7 +6,6 @@
th_stopped_velocity: 0.01
th_stopped_time: 1.0
collision_check_margins: [2.0, 1.0, 0.5, 0.1]
- collision_check_distance_from_end: -10.0
collision_check_margin_from_front_object: 5.0
th_moving_object_velocity: 1.0
th_distance_to_middle_of_the_road: 0.5
@@ -39,6 +38,7 @@
backward_path_update_duration: 3.0
ignore_distance_from_lane_end: 15.0
# turns signal
+ prepare_time_before_start: 0.0
th_turn_signal_on_lateral_offset: 1.0
intersection_search_length: 30.0
length_ratio_for_turn_signal_deactivation_near_intersection: 0.5
@@ -93,7 +93,7 @@
delay_until_departure: 1.0
# For target object filtering
target_filtering:
- safety_check_time_horizon: 5.0
+ safety_check_time_horizon: 10.0
safety_check_time_resolution: 1.0
# detection range
object_check_forward_distance: 10.0
@@ -127,7 +127,6 @@
# safety check configuration
enable_safety_check: true
# collision check parameters
- check_all_predicted_path: true
publish_debug_marker: false
rss_params:
rear_vehicle_reaction_time: 2.0
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml
index 7bd7d88230..424029300a 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml
@@ -4,7 +4,7 @@
use_pass_judge_line: true
stop_line_margin: 1.0 # [m]
backward_length: 50.0 # [m]
- ignore_width_from_center_line: 0.7 # [m]
+ ignore_width_from_center_line: 0.0 # [m]
max_future_movement_time: 10.0 # [second]
threshold_yaw_diff: 0.523 # [rad]
adjacent_extend_width: 1.5 # [m]
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 921b728a34..6de22a67dc 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
@@ -41,7 +41,7 @@
ego_pass_first_margin_y: [3.0] # [[s]] time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition)
ego_pass_first_additional_margin: 0.5 # [s] additional time margin for ego pass first situation to suppress chattering
ego_pass_later_margin_x: [0.0] # [[s]] time to vehicle margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition)
- ego_pass_later_margin_y: [10.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition)
+ ego_pass_later_margin_y: [13.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition)
ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering
no_stop_decision: # parameters to determine if it is safe to attempt stopping before the crosswalk
@@ -53,11 +53,10 @@
stop_object_velocity_threshold: 0.25 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.25 m/s = 0.9 kmph)
min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph)
## param for yielding
- disable_stop_for_yield_cancel: true # for the crosswalks with traffic signal
disable_yield_for_new_stopped_object: true # for the crosswalks with traffic signal
# If the pedestrian does not move for X seconds after the ego has stopped in front the crosswalk, the module judge that the pedestrian has no intention to walk and allows the ego to proceed.
- distance_map_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order
- timeout_map_for_no_intention_to_walk: [1.0, 0.0] # [s]
+ distance_set_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order
+ timeout_set_for_no_intention_to_walk: [1.0, 0.0] # [s]
timeout_ego_stop_for_yield: 1.0 # [s] If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough.
# param for target object filtering
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 86bcf801f4..68d4070cbf 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
@@ -15,6 +15,14 @@
enable_pass_judge_before_default_stopline: false
stuck_vehicle:
+ target_type:
+ car: true
+ bus: true
+ truck: true
+ trailer: true
+ motorcycle: false
+ bicycle: false
+ unknown: false
turn_direction:
left: true
right: true
@@ -27,6 +35,14 @@
disable_against_private_lane: true
yield_stuck:
+ target_type:
+ car: true
+ bus: true
+ truck: true
+ trailer: true
+ motorcycle: false
+ bicycle: false
+ unknown: false
turn_direction:
left: true
right: true
@@ -37,6 +53,14 @@
consider_wrong_direction_vehicle: false
collision_detection_hold_time: 0.5
min_predicted_path_confidence: 0.05
+ target_type:
+ car: true
+ bus: true
+ truck: true
+ trailer: true
+ motorcycle: true
+ bicycle: true
+ unknown: false
velocity_profile:
use_upstream: true
minimum_upstream_velocity: 0.01
@@ -56,7 +80,9 @@
duration: 3.0
object_dist_to_stopline: 10.0
ignore_on_amber_traffic_light:
- object_expected_deceleration: 2.0
+ object_expected_deceleration:
+ car: 2.0
+ bike: 5.0
ignore_on_red_traffic_light:
object_margin_to_path: 2.0
avoid_collision_by_acceleration:
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 1ac32ba562..2ff87e9b01 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
@@ -95,7 +95,12 @@
obstacle_velocity_threshold : 3.5 # minimum velocity threshold of obstacles outside the trajectory to cruise or stop [m/s]
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
+ 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
+ stopped_obstacle_velocity_threshold: 0.5
slow_down:
max_lat_margin: 1.1 # lateral margin between obstacle and trajectory band with ego's width
lat_hysteresis_margin: 0.2
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
index 69e3831591..a3c712d466 100644
--- 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
@@ -24,6 +24,8 @@
/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_error_ellipse: { sf_at: "warn", lf_at: "none", spf_at: "none" }
+ /autoware/localization/performance_monitoring/localization_stability: { sf_at: "warn", lf_at: "none", spf_at: "none" }
+ /autoware/localization/performance_monitoring/sensor_fusion_status: { sf_at: "warn", lf_at: "none", spf_at: "none" }
/autoware/map/node_alive_monitoring: default
diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml
index d8229425af..2826e9348c 100644
--- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml
+++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml
@@ -24,6 +24,7 @@
/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_error_ellipse: default
+ /autoware/localization/performance_monitoring/localization_stability: default
/autoware/localization/performance_monitoring/sensor_fusion_status: { sf_at: "error", lf_at: "none", spf_at: "none" }
/autoware/map/node_alive_monitoring: default
diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index 7de7741be2..a5daf3dd16 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -4,7 +4,6 @@
-
@@ -56,12 +55,10 @@
-
-
-
-
-
-
+
+
+
+
diff --git a/autoware_launch/launch/components/tier4_localization_component.launch.xml b/autoware_launch/launch/components/tier4_localization_component.launch.xml
index 70170a5fef..3ccd98104d 100644
--- a/autoware_launch/launch/components/tier4_localization_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_localization_component.launch.xml
@@ -19,16 +19,25 @@
-
-
-
-
+
+
+
+
@@ -43,6 +52,9 @@
+
+
+
diff --git a/autoware_launch/launch/components/tier4_map_component.launch.xml b/autoware_launch/launch/components/tier4_map_component.launch.xml
index 455b848c63..ba5611b6c0 100644
--- a/autoware_launch/launch/components/tier4_map_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_map_component.launch.xml
@@ -8,6 +8,7 @@
+
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index a84911a414..3b0f8eca46 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -14,7 +14,6 @@
-
@@ -128,10 +127,6 @@
name="object_recognition_tracking_radar_object_tracker_node_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml"
/>
-
+
+
+
+
+
diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml
index 4e65c30c02..3d57f6198e 100644
--- a/autoware_launch/launch/components/tier4_planning_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml
@@ -7,7 +7,6 @@
-
@@ -27,6 +26,7 @@
+
diff --git a/autoware_launch/launch/components/tier4_sensing_component.launch.xml b/autoware_launch/launch/components/tier4_sensing_component.launch.xml
index fe520e1fdc..4cd6eccbaa 100644
--- a/autoware_launch/launch/components/tier4_sensing_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_sensing_component.launch.xml
@@ -5,7 +5,6 @@
-
diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml
index 57cbc38af6..77d17d7897 100644
--- a/autoware_launch/launch/logging_simulator.launch.xml
+++ b/autoware_launch/launch/logging_simulator.launch.xml
@@ -21,7 +21,6 @@
-
@@ -55,7 +54,6 @@
-
diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml
index d19c7308f0..63443c928f 100644
--- a/autoware_launch/launch/planning_simulator.launch.xml
+++ b/autoware_launch/launch/planning_simulator.launch.xml
@@ -13,6 +13,8 @@
+
+
@@ -50,8 +52,6 @@
-
-
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index 064f87d3ff..f73b720b5d 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -58,58 +58,6 @@ Visualization Manager:
Value: false
- Class: rviz_common/Group
Displays:
- - Class: rviz_plugins/SteeringAngle
- Enabled: true
- Name: SteeringAngle
- Scale: 17
- Text Color: 25; 255; 240
- Topic:
- Depth: 5
- Durability Policy: Volatile
- History Policy: Keep Last
- Reliability Policy: Reliable
- Value: /vehicle/status/steering_status
- Value: true
- Value height offset: 0
- - Class: rviz_plugins/ConsoleMeter
- Enabled: true
- Name: ConsoleMeter
- Scale: 3
- Text Color: 25; 255; 240
- Topic:
- Depth: 5
- Durability Policy: Volatile
- History Policy: Keep Last
- Reliability Policy: Reliable
- Value: /vehicle/status/velocity_status
- Value: true
- Value height offset: 0
- - Class: rviz_plugins/AccelerationMeter
- Enabled: false
- Name: AccelerationMeter
- Topic:
- Depth: 5
- Durability Policy: Volatile
- History Policy: Keep Last
- Reliability Policy: Reliable
- Value: /localization/acceleration
- - Alpha: 0.999
- Class: rviz_plugins/VelocityHistory
- Color Border Vel Max: 3
- Constant Color:
- Color: 255; 255; 255
- Value: true
- Enabled: true
- Name: VelocityHistory
- Scale: 0.30000001192092896
- Timeout: 10
- Topic:
- Depth: 5
- Durability Policy: Volatile
- History Policy: Keep Last
- Reliability Policy: Reliable
- Value: /vehicle/status/velocity_status
- Value: true
- Alpha: 0.30000001192092896
Class: rviz_default_plugins/RobotModel
Collision Enabled: false
@@ -296,27 +244,22 @@ Visualization Manager:
Value: true
Wave Color: 255; 255; 255
Wave Velocity: 40
- - Class: rviz_plugins/MaxVelocity
+ - Class: autoware_overlay_rviz_plugin/SignalDisplay
Enabled: true
- Name: MaxVelocity
- Text Color: 255; 255; 255
- Topic:
- Depth: 5
- Durability Policy: Volatile
- History Policy: Keep Last
- Reliability Policy: Reliable
- Value: /planning/scenario_planning/current_max_velocity
- Value: true
- - Class: rviz_plugins/TurnSignal
- Enabled: true
- Name: TurnSignal
- Topic:
- Depth: 5
- Durability Policy: Volatile
- History Policy: Keep Last
- Reliability Policy: Reliable
- Value: /vehicle/status/turn_indicators_status
+ Gear Topic Test: /vehicle/status/gear_status
+ Hazard Lights Topic: /vehicle/status/hazard_lights_status
+ Height: 175
+ Left: 10
+ Name: SignalDisplay
+ Signal Color: 0; 230; 120
+ Speed Limit Topic: /planning/scenario_planning/current_max_velocity
+ Speed Topic: /vehicle/status/velocity_status
+ Steering Topic: /vehicle/status/steering_status
+ Top: 10
+ Traffic Topic: /perception/traffic_light_recognition/traffic_signals
+ Turn Signals Topic: /vehicle/status/turn_indicators_status
Value: true
+ Width: 517
Enabled: true
Name: Vehicle
- Class: rviz_plugins/MrmSummaryOverlayDisplay
@@ -2707,15 +2650,10 @@ Visualization Manager:
TF: true
Value: false
Vehicle:
- AccelerationMeter: true
- ConsoleMeter: true
- MaxVelocity: true
PolarGridDisplay: true
- SteeringAngle: true
- TurnSignal: true
Value: true
VehicleModel: true
- VelocityHistory: true
+ SignalDisplay: true
Value: true
Zoom Factor: 1
- Alpha: 1
diff --git a/autoware_launch/rviz/image/autoware.png b/autoware_launch/rviz/image/autoware.png
index cf2d1e8eff..3b27ce5fbc 100644
Binary files a/autoware_launch/rviz/image/autoware.png and b/autoware_launch/rviz/image/autoware.png differ