diff --git a/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml b/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
index 09db0feb34..1a870aff7a 100644
--- a/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
+++ b/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
@@ -1,5 +1,6 @@
/**:
ros__parameters:
+ publish_debug_pointcloud: false
use_predicted_trajectory: true
use_imu_path: true
voxel_grid_x: 0.05
@@ -11,7 +12,9 @@
t_response: 1.0
a_ego_min: -3.0
a_obj_min: -1.0
- prediction_time_horizon: 1.5
- prediction_time_interval: 0.1
+ imu_prediction_time_horizon: 1.5
+ imu_prediction_time_interval: 0.1
+ mpc_prediction_time_horizon: 1.5
+ mpc_prediction_time_interval: 0.1
collision_keeping_sec: 0.0
aeb_hz: 10.0
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 191e894622..7ad685217f 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
@@ -6,6 +6,8 @@
check_external_emergency_heartbeat: false
use_start_request: false
enable_cmd_limit_filter: true
+ filter_activated_count_threshold: 5
+ filter_activated_velocity_threshold: 1.0
external_emergency_stop_heartbeat_timeout: 0.0
stop_hold_acceleration: -1.5
emergency_acceleration: -2.4
diff --git a/autoware_launch/config/localization/ekf_localizer.param.yaml b/autoware_launch/config/localization/ekf_localizer.param.yaml
index 667217d259..1c16624605 100644
--- a/autoware_launch/config/localization/ekf_localizer.param.yaml
+++ b/autoware_launch/config/localization/ekf_localizer.param.yaml
@@ -24,9 +24,9 @@
# for diagnostics
pose_no_update_count_threshold_warn: 50
- pose_no_update_count_threshold_error: 250
+ pose_no_update_count_threshold_error: 100
twist_no_update_count_threshold_warn: 50
- twist_no_update_count_threshold_error: 250
+ twist_no_update_count_threshold_error: 100
# 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/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
index 0ba1b1a2e1..1a6c26cd9c 100644
--- a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
+++ b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
@@ -72,6 +72,14 @@
0.0, 0.0, 0.0, 0.0, 0.0, 0.000625,
]
+ # 2D Real-time covariance estimation with multiple searches (output_pose_covariance is the minimum value)
+ use_covariance_estimation: false
+
+ # Offset arrangement in covariance estimation [m]
+ # initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements.
+ initial_pose_offset_model_x: [0.0, 0.0, 0.5, -0.5, 1.0, -1.0]
+ initial_pose_offset_model_y: [0.5, -0.5, 0.0, 0.0, 0.0, 0.0]
+
# Regularization switch
regularization_enabled: false
diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/data_association_matrix.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/data_association_matrix.param.yaml
index 104d790d18..69628414e6 100644
--- a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/data_association_matrix.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/data_association_matrix.param.yaml
@@ -14,10 +14,10 @@
max_dist_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[4.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN
- 4.0, 4.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR
- 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK
- 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS
- 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER
+ 4.0, 8.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #CAR
+ 4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #TRUCK
+ 4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #BUS
+ 4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #TRAILER
3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #MOTORBIKE
3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE
2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN
diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/default_tracker.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/default_tracker.param.yaml
index 757125202d..6c26034860 100644
--- a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/default_tracker.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/default_tracker.param.yaml
@@ -1,9 +1,9 @@
/**:
ros__parameters:
- car_tracker: "linear_motion_tracker"
- truck_tracker: "linear_motion_tracker"
- bus_tracker: "linear_motion_tracker"
- trailer_tracker: "linear_motion_tracker"
- pedestrian_tracker: "linear_motion_tracker"
- bicycle_tracker: "linear_motion_tracker"
- motorcycle_tracker: "linear_motion_tracker"
+ car_tracker: "constant_turn_rate_motion_tracker"
+ truck_tracker: "constant_turn_rate_motion_tracker"
+ bus_tracker: "constant_turn_rate_motion_tracker"
+ trailer_tracker: "constant_turn_rate_motion_tracker"
+ pedestrian_tracker: "constant_turn_rate_motion_tracker"
+ bicycle_tracker: "constant_turn_rate_motion_tracker"
+ motorcycle_tracker: "constant_turn_rate_motion_tracker"
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 f80adffb41..d2c0841cf3 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
@@ -4,12 +4,11 @@
# basic settings
world_frame_id: "map"
tracker_lifetime: 1.0 # [sec]
- # if empty, use default config declared in this package
- tracking_config_directory: ""
+ measurement_count_threshold: 3 # object will be published if it is tracked more than this threshold
# delay compensate parameters
publish_rate: 10.0
- enable_delay_compensation: false
+ enable_delay_compensation: true
# logging
enable_logging: false
@@ -18,10 +17,10 @@
# filtering
## 1. distance based filtering: remove closer objects than this threshold
use_distance_based_noise_filtering: true
- minimum_range_threshold: 70.0 # [m]
+ minimum_range_threshold: 60.0 # [m]
## 2. lanelet map based filtering
use_map_based_noise_filtering: true
max_distance_from_lane: 5.0 # [m]
max_angle_diff_from_lane: 0.785398 # [rad] (45 deg)
- max_lateral_velocity: 5.0 # [m/s]
+ max_lateral_velocity: 7.0 # [m/s]
diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/constant_turn_rate_motion_tracker.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/constant_turn_rate_motion_tracker.yaml
new file mode 100644
index 0000000000..f80f881cab
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/constant_turn_rate_motion_tracker.yaml
@@ -0,0 +1,36 @@
+default:
+ # This file defines the parameters for the linear motion tracker.
+ # All this parameter coordinate is assumed to be in the vehicle coordinate system.
+ # So, the x axis is pointing to the front of the vehicle, y axis is pointing to the left of the vehicle.
+ ekf_params:
+ # random walk noise is used to model the acceleration noise
+ process_noise_std: # [m/s^2]
+ x: 0.5
+ y: 0.5
+ yaw: 0.1
+ vx: 1.0 # assume 1m/s velocity noise
+ wz: 0.4
+ measurement_noise_std:
+ x: 4.0 # [m]
+ y: 4.0 # [m]
+ # y: 0.02 # rad/m if use_polar_coordinate_in_measurement_noise is true
+ yaw: 0.2 # [rad]
+ vx: 10 # [m/s]
+ initial_covariance_std:
+ x: 3.0 # [m]
+ y: 6.0 # [m]
+ yaw: 10.0 # [rad]
+ vx: 100.0 # [m/s]
+ wz: 10.0 # [rad/s]
+ # input flag
+ trust_yaw_input: false # set true if yaw input of sensor is reliable
+ trust_twist_input: false # set true if twist input of sensor is reliable
+ use_polar_coordinate_in_measurement_noise: false # set true if you want to define the measurement noise in polar coordinate
+ assume_zero_yaw_rate: false # set true if you want to assume zero yaw rate
+ # output limitation
+ limit:
+ max_speed: 80.0 # [m/s]
+ # low pass filter is used to smooth the yaw and shape estimation
+ low_pass_filter:
+ time_constant: 1.0 # [s]
+ sampling_time: 0.1 # [s]
diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/linear_motion_tracker.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/linear_motion_tracker.yaml
index 71367f4575..5e813558a2 100644
--- a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/linear_motion_tracker.yaml
+++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/linear_motion_tracker.yaml
@@ -7,22 +7,28 @@ default:
process_noise_std: # [m/s^2]
ax: 0.98 # assume 0.1G acceleration noise
ay: 0.98
- vx: 0.1 # assume 0.1m/s velocity noise
- vy: 0.1
+ vx: 1.0 # assume 1m/s velocity noise
+ vy: 1.0
x: 1.0 # assume 1m position noise
y: 1.0
measurement_noise_std:
x: 0.6 # [m]
- y: 0.9 # [m]
- vx: 0.4 # [m/s]
- vy: 1 # [m/s]
+ # y: 4.0 # [m]
+ y: 0.01 # rad/m if use_polar_coordinate_in_measurement_noise is true
+ vx: 10 # [m/s]
+ vy: 100 # [m/s]
initial_covariance_std:
x: 3.0 # [m]
y: 6.0 # [m]
- vx: 1.0 # [m/s]
- vy: 5.0 # [m/s]
- ax: 0.5 # [m/s^2]
- ay: 1.0 # [m/s^2]
+ vx: 1000.0 # [m/s]
+ vy: 1000.0 # [m/s]
+ ax: 1000.0 # [m/s^2]
+ ay: 1000.0 # [m/s^2]
+ estimate_acc: false # set true if you want to estimate the acceleration
+ # input flag
+ trust_yaw_input: false # set true if yaw input of sensor is reliable
+ trust_twist_input: false # set true if twist input of sensor is reliable
+ use_polar_coordinate_in_measurement_noise: true # set true if you want to define the measurement noise in polar coordinate
# output limitation
limit:
max_speed: 80.0 # [m/s]
diff --git a/autoware_launch/config/planning/scenario_planning/common/costmap_generator.param.yaml b/autoware_launch/config/planning/scenario_planning/common/costmap_generator.param.yaml
new file mode 100644
index 0000000000..cf4f73dc79
--- /dev/null
+++ b/autoware_launch/config/planning/scenario_planning/common/costmap_generator.param.yaml
@@ -0,0 +1,22 @@
+/**:
+ ros__parameters:
+ costmap_frame: "map"
+ vehicle_frame: "base_link"
+ map_frame: "map"
+ update_rate: 10.0
+ activate_by_scenario: False
+ grid_min_value: 0.0
+ grid_max_value: 1.0
+ grid_resolution: 0.2
+ grid_length_x: 70.0
+ grid_length_y: 70.0
+ grid_position_x: 0.0
+ grid_position_y: 0.0
+ maximum_lidar_height_thres: 0.3
+ minimum_lidar_height_thres: -2.2
+ use_wayarea: true
+ use_parkinglot: true
+ use_objects: true
+ use_points: true
+ expand_polygon_size: 1.0
+ size_of_expansion_kernel: 9
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 fe9c37d200..98d75415d0 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
@@ -9,7 +9,6 @@
# avoidance module common setting
enable_bound_clipping: false
- enable_force_avoidance_for_stopped_vehicle: false
enable_yield_maneuver: true
enable_yield_maneuver_during_shifting: false
enable_cancel_maneuver: true
@@ -37,6 +36,7 @@
avoid_margin_lateral: 1.0 # [m]
safety_buffer_lateral: 0.7 # [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:
is_target: true
execute_num: 1
@@ -47,6 +47,7 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
+ use_conservative_buffer_longitudinal: true
bus:
is_target: true
execute_num: 1
@@ -57,6 +58,7 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
+ use_conservative_buffer_longitudinal: true
trailer:
is_target: true
execute_num: 1
@@ -67,6 +69,7 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
+ use_conservative_buffer_longitudinal: true
unknown:
is_target: true
execute_num: 1
@@ -77,6 +80,7 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
+ use_conservative_buffer_longitudinal: true
bicycle:
is_target: true
execute_num: 1
@@ -87,6 +91,7 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
+ use_conservative_buffer_longitudinal: true
motorcycle:
is_target: true
execute_num: 1
@@ -97,6 +102,7 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
+ use_conservative_buffer_longitudinal: true
pedestrian:
is_target: true
execute_num: 1
@@ -107,16 +113,12 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
+ use_conservative_buffer_longitudinal: true
lower_distance_for_polygon_expansion: 30.0 # [m]
upper_distance_for_polygon_expansion: 100.0 # [m]
# For target object filtering
target_filtering:
- # params for avoidance of not-parked objects
- threshold_time_force_avoidance_for_stopped_vehicle: 1.0 # [s]
- object_ignore_section_traffic_light_in_front_distance: 100.0 # [m]
- object_ignore_section_crosswalk_in_front_distance: 30.0 # [m]
- object_ignore_section_crosswalk_behind_distance: 30.0 # [m]
# detection range
object_check_goal_distance: 20.0 # [m]
# filtering parking objects
@@ -133,6 +135,17 @@
max_forward_distance: 150.0 # [m]
backward_distance: 10.0 # [m]
+ # params for avoidance of vehicle type objects that are ambiguous as to whether they are parked.
+ force_avoidance:
+ enable: false # [-]
+ time_threshold: 1.0 # [s]
+ ignore_area:
+ traffic_light:
+ front_distance: 100.0 # [m]
+ crosswalk:
+ front_distance: 30.0 # [m]
+ behind_distance: 30.0 # [m]
+
# For safety check
safety_check:
# safety check configuration
@@ -178,11 +191,18 @@
# avoidance distance parameters
longitudinal:
prepare_time: 2.0 # [s]
- remain_buffer_distance: 30.0 # [m]
min_prepare_distance: 1.0 # [m]
min_slow_down_speed: 1.38 # [m/s]
buf_slow_down_speed: 0.56 # [m/s]
nominal_avoidance_speed: 8.33 # [m/s]
+ # return dead line
+ return_dead_line:
+ goal:
+ enable: true # [-]
+ buffer: 30.0 # [m]
+ traffic_light:
+ enable: true # [-]
+ buffer: 3.0 # [m]
# For yield maneuver
yield:
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml
index 3a7393a4c9..6acbe9783d 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml
@@ -3,6 +3,8 @@
verbose: false
max_iteration_num: 100
+ traffic_light_signal_timeout: 1.0
+
groot_zmq_publisher_port: 1666
groot_zmq_server_port: 1667
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 0f1b441bed..295c9caf84 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
@@ -48,7 +48,7 @@
maximum_deceleration: 1.0
maximum_jerk: 1.0
path_priority: "efficient_path" # "efficient_path" or "close_goal"
- efficient_path_order: ["SHIFT", "ARC_FORWARD", "ARC_BACKWARD"] # only lane based pull over(exculde freespace parking)
+ efficient_path_order: ["SHIFT", "ARC_FORWARD", "ARC_BACKWARD"] # only lane based pull over(exclude freespace parking)
# shift parking
shift_parking:
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 e09f6e479b..b7ae55536e 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
@@ -5,6 +5,7 @@
prepare_duration: 4.0 # [s]
backward_length_buffer_for_end_of_lane: 3.0 # [m]
+ backward_length_buffer_for_blocking_object: 3.0 # [m]
lane_change_finish_judge_buffer: 2.0 # [m]
lane_changing_lateral_jerk: 0.5 # [m/s3]
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 c49be22d0a..960dd89b00 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
@@ -56,6 +56,8 @@
object_dist_to_stopline: 10.0 # [m]
ignore_on_amber_traffic_light:
object_expected_deceleration: 2.0 # [m/ss]
+ ignore_on_red_traffic_light:
+ object_margin_to_path: 2.0
occlusion:
enable: false
@@ -81,6 +83,9 @@
attention_lane_curvature_calculation_ds: 0.5
static_occlusion_with_traffic_light_timeout: 0.5
+ debug:
+ ttc: [0]
+
enable_rtc:
intersection: false # 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
intersection_to_occlusion: false
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 b8da5f4e7c..6a763eace4 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_accuracy: 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/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index e3df873492..5959d58e18 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -85,6 +85,10 @@
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"
/>
+
-
-
-
-
+
+
+
+
+
@@ -16,6 +17,9 @@
+
+
+
@@ -24,42 +28,41 @@
+
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
@@ -73,15 +76,10 @@
-
-
-
-
-
-
+
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index cdb1ffe690..fda080bfcf 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -401,6 +401,7 @@ Visualization Manager:
walkway_lanelets: true
hatched_road_markings_bound: true
hatched_road_markings_area: false
+ intersection_area: false
Topic:
Depth: 5
Durability Policy: Transient Local
@@ -902,7 +903,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Best Effort
- Value: /perception/traffic_light_recognition/debug/rois
+ Value: /perception/traffic_light_recognition/traffic_light/debug/rois
Value: true
- Class: rviz_default_plugins/MarkerArray
Enabled: true