diff --git a/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
index 0d86229b1d..d5c6356c38 100644
--- a/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
+++ b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
@@ -6,6 +6,7 @@
use_pointcloud_data: true
use_predicted_object_data: false
use_object_velocity_calculation: true
+ check_autoware_state: true
min_generated_path_length: 0.5
imu_prediction_time_horizon: 1.5
imu_prediction_time_interval: 0.1
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 37772ac574..135aecc56b 100644
--- a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml
+++ b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml
@@ -75,4 +75,4 @@
average_num: 1000
steering_offset_limit: 0.02
- debug_publish_predicted_trajectory: false # publish debug predicted trajectory in Frenet coordinate
+ debug_publish_predicted_trajectory: true # publish debug predicted trajectory in Frenet coordinate
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 dd99e6d160..8b11cdb85a 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
@@ -4,7 +4,6 @@
system_emergency_heartbeat_timeout: 0.5
use_emergency_handling: true
check_external_emergency_heartbeat: $(var check_external_emergency_heartbeat)
- use_start_request: false
enable_cmd_limit_filter: true
filter_activated_count_threshold: 5
filter_activated_velocity_threshold: 1.0
@@ -12,7 +11,6 @@
stop_hold_acceleration: -1.5
emergency_acceleration: -2.4
moderate_stop_service_acceleration: -1.5
- stopped_state_entry_duration_time: 0.1
stop_check_duration: 1.0
nominal:
vel_lim: 25.0
diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_sigma.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_sigma.param.yaml
index 5c3d8645de..bd5fc5f356 100644
--- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_sigma.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_sigma.param.yaml
@@ -1,28 +1,21 @@
/**:
ros__parameters:
- class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
- point_feature_size: 4
- max_voxel_size: 40000
- point_cloud_range: [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0]
- voxel_size: [0.32, 0.32, 10.0]
- downsample_factor: 1
- encoder_in_feature_size: 9
- # post-process params
- circle_nms_dist_threshold: 0.5
- iou_nms_target_class_names: ["CAR"]
- 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_variance: true
- has_twist: true
- trt_precision: fp16
- cloud_capacity: 2000000
- 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"
+ trt_precision: fp16
+ cloud_capacity: 2000000
+ post_process_params:
+ # post-process params
+ circle_nms_dist_threshold: 0.5
+ iou_nms_target_class_names: ["CAR"]
+ 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
+ densification_params:
+ world_frame_id: map
+ num_past_frames: 1
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 e123b0dda6..5d68825f4d 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
@@ -50,3 +50,8 @@
consider_only_routable_neighbours: false
reference_path_resolution: 0.5 #[m]
+
+ # debug parameters
+ publish_processing_time: true
+ publish_processing_time_detail: true
+ publish_debug_markers: true
diff --git a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/input_channels.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/input_channels.param.yaml
index b57f37675d..6f9bfcf621 100644
--- a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/input_channels.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/input_channels.param.yaml
@@ -40,8 +40,8 @@
name: "apollo"
short_name: "Lap"
# LIDAR-CAMERA - DNN
- # cspell:ignore lidar_pointpainitng pointpainting
- lidar_pointpainitng:
+ # cspell:ignore lidar_pointpainting pointpainting
+ lidar_pointpainting:
topic: "/perception/object_recognition/detection/pointpainting/objects"
can_spawn_new_tracker: true
optional:
diff --git a/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger.param.yaml
index e4ea2becd7..5286206876 100644
--- a/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger.param.yaml
@@ -2,6 +2,7 @@
/**:
ros__parameters:
base_link_frame_id: "base_link"
+ merge_frame_id: "map"
time_sync_threshold: 0.999
sub_object_timeout_sec: 0.8
publish_interpolated_sub_objects: true #for debug
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
index d23e2e9676..5d37138738 100644
--- a/autoware_launch/config/planning/scenario_planning/common/costmap_generator.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/common/costmap_generator.param.yaml
@@ -18,5 +18,5 @@
use_parkinglot: true
use_objects: true
use_points: true
- expand_polygon_size: 1.0
+ expand_polygon_size: 0.5
size_of_expansion_kernel: 9
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml
index ef113f6ff2..497c0eef02 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml
@@ -28,6 +28,7 @@
hard_margin_for_parked_vehicle: 0.7 # [m]
max_expand_ratio: 0.0 # [-] FOR DEVELOPER
envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER
+ th_error_eclipse_long_radius : 0.6 # [m]
truck:
th_moving_speed: 1.0
th_moving_time: 2.0
@@ -38,6 +39,7 @@
hard_margin_for_parked_vehicle: 0.7
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
+ th_error_eclipse_long_radius : 0.6
bus:
th_moving_speed: 1.0
th_moving_time: 2.0
@@ -48,6 +50,7 @@
hard_margin_for_parked_vehicle: 0.7
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
+ th_error_eclipse_long_radius : 0.6
trailer:
th_moving_speed: 1.0
th_moving_time: 2.0
@@ -58,6 +61,7 @@
hard_margin_for_parked_vehicle: 0.7
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
+ th_error_eclipse_long_radius : 0.6
unknown:
th_moving_speed: 0.28
th_moving_time: 1.0
@@ -68,6 +72,7 @@
hard_margin_for_parked_vehicle: -0.2
max_expand_ratio: 0.0
envelope_buffer_margin: 0.1
+ th_error_eclipse_long_radius : 0.6
bicycle:
th_moving_speed: 0.28
th_moving_time: 1.0
@@ -78,6 +83,7 @@
hard_margin_for_parked_vehicle: 0.5
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
+ th_error_eclipse_long_radius : 0.6
motorcycle:
th_moving_speed: 1.0
th_moving_time: 1.0
@@ -88,6 +94,7 @@
hard_margin_for_parked_vehicle: 0.3
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
+ th_error_eclipse_long_radius : 0.6
pedestrian:
th_moving_speed: 0.28
th_moving_time: 1.0
@@ -98,6 +105,7 @@
hard_margin_for_parked_vehicle: 0.5
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
+ th_error_eclipse_long_radius : 0.6
lower_distance_for_polygon_expansion: 30.0 # [m] FOR DEVELOPER
upper_distance_for_polygon_expansion: 100.0 # [m] FOR DEVELOPER
@@ -142,16 +150,16 @@
# "auto" : generate candidate path. if RTC is running as AUTO mode, the ego avoids it automatically.
# "manual" : generate candidate path and wait operator approval even if RTC is running as AUTO mode.
# "ignore" : never avoid it.
- policy: "auto" # [-]
+ policy: "manual" # [-]
condition:
th_stopped_time: 3.0 # [s]
th_moving_distance: 1.0 # [m]
ignore_area:
traffic_light:
- front_distance: 100.0 # [m]
+ front_distance: 20.0 # [m]
crosswalk:
- front_distance: 30.0 # [m]
- behind_distance: 30.0 # [m]
+ front_distance: 20.0 # [m]
+ behind_distance: 0.0 # [m]
wait_and_see:
target_behaviors: ["MERGING", "DEVIATING"] # [-]
th_closest_distance: 10.0 # [m]
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 5cee76de9b..b1b03c21c1 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
@@ -36,7 +36,7 @@
# object recognition
object_recognition:
use_object_recognition: true
- collision_check_soft_margins: [2.0, 1.5, 1.0]
+ collision_check_soft_margins: [5.0, 4.5, 4.0, 3.5, 3.0, 2.5, 2.0, 1.5, 1.0] # the maximum margin when ego and objects are oriented.
collision_check_hard_margins: [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
@@ -55,6 +55,7 @@
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(exclude freespace parking)
+ lane_departure_check_expansion_margin: 0.0
# shift parking
shift_parking:
@@ -112,9 +113,11 @@
use_back: true
adapt_expansion_distance: true
expansion_distance: 0.5
+ near_goal_distance: 3.0
distance_heuristic_weight: 2.0
smoothness_weight: 0.5
obstacle_distance_weight: 1.75
+ goal_lat_distance_weight: 5.0
# -- RRT* search Configurations --
rrtstar:
enable_update: true
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 d301e96deb..0cea2aa62b 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
@@ -6,7 +6,6 @@
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]
@@ -27,6 +26,11 @@
min_longitudinal_acc: -1.0
max_longitudinal_acc: 1.0
+ skip_process:
+ longitudinal_distance_diff_threshold:
+ prepare: 1.0
+ lane_changing: 1.0
+
# safety check
safety_check:
allow_loose_check_for_cancel: true
@@ -38,7 +42,15 @@
rear_vehicle_safety_time_margin: 1.0
lateral_distance_max_threshold: 2.0
longitudinal_distance_min_threshold: 3.0
- longitudinal_velocity_delta_time: 0.8
+ longitudinal_velocity_delta_time: 0.0
+ parked:
+ expected_front_deceleration: -1.0
+ expected_rear_deceleration: -2.0
+ rear_vehicle_reaction_time: 1.0
+ rear_vehicle_safety_time_margin: 0.8
+ lateral_distance_max_threshold: 1.0
+ longitudinal_distance_min_threshold: 3.0
+ longitudinal_velocity_delta_time: 0.0
cancel:
expected_front_deceleration: -1.0
expected_rear_deceleration: -2.0
@@ -46,7 +58,7 @@
rear_vehicle_safety_time_margin: 0.8
lateral_distance_max_threshold: 1.0
longitudinal_distance_min_threshold: 2.5
- longitudinal_velocity_delta_time: 0.6
+ longitudinal_velocity_delta_time: 0.0
stuck:
expected_front_deceleration: -1.0
expected_rear_deceleration: -1.0
@@ -54,7 +66,7 @@
rear_vehicle_safety_time_margin: 1.0
lateral_distance_max_threshold: 2.0
longitudinal_distance_min_threshold: 3.0
- longitudinal_velocity_delta_time: 0.8
+ longitudinal_velocity_delta_time: 0.0
# lane expansion for object filtering
lane_expansion:
@@ -83,10 +95,10 @@
general_lanes: false
intersection: true
turns: true
- prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s]
+ stopped_object_velocity_threshold: 1.0 # [m/s]
check_objects_on_current_lanes: false
check_objects_on_other_lanes: false
- use_all_predicted_path: true
+ use_all_predicted_path: false
# lane change regulations
regulation:
@@ -108,8 +120,11 @@
max_lateral_jerk: 100.0 # [m/s3]
overhang_tolerance: 0.0 # [m]
unsafe_hysteresis_threshold: 5 # [/]
+ deceleration_sampling_num: 5 # [/]
- finish_judge_lateral_threshold: 0.2 # [m]
+ lane_change_finish_judge_buffer: 2.0 # [m]
+ finish_judge_lateral_threshold: 0.1 # [m]
+ finish_judge_lateral_angle_deviation: 1.0 # [deg]
# debug
publish_debug_marker: 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 59ef4157b8..9f270b0637 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
@@ -3,80 +3,80 @@
# NOTE: The smaller the priority number is, the higher the module priority is.
/**:
ros__parameters:
+ # NOTE: modules which are not set true in the preset is ignored in the slot configuration
+ slots:
+ # NOTE: array of array is not supported
+ - slot1
+ - slot2
+ - slot3
+ - slot4
+ slot1:
+ - "start_planner"
+ slot2:
+ - "side_shift"
+ - "avoidance_by_lane_change"
+ - "static_obstacle_avoidance"
+ - "lane_change_left"
+ - "lane_change_right"
+ - "external_request_lane_change_left"
+ - "external_request_lane_change_right"
+ slot3:
+ - "goal_planner"
+ slot4:
+ - "dynamic_obstacle_avoidance"
+
external_request_lane_change_left:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: true
- keep_last: false
- priority: 6
external_request_lane_change_right:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: true
- keep_last: false
- priority: 6
lane_change_left:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
- keep_last: false
- priority: 5
lane_change_right:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
- keep_last: false
- priority: 5
start_planner:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
- keep_last: false
- priority: 0
side_shift:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
- keep_last: false
- priority: 2
goal_planner:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
- keep_last: true
- priority: 1
static_obstacle_avoidance:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
- keep_last: false
- priority: 4
avoidance_by_lane_change:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
- keep_last: false
- priority: 3
dynamic_obstacle_avoidance:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
- keep_last: true
- priority: 7
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
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 8cfae9e9ad..10eb7486db 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
@@ -83,9 +83,11 @@
use_back: true
adapt_expansion_distance: true
expansion_distance: 0.5
+ near_goal_distance: 3.0
distance_heuristic_weight: 2.0
smoothness_weight: 0.5
obstacle_distance_weight: 1.75
+ goal_lat_distance_weight: 5.0
# -- RRT* search Configurations --
rrtstar:
enable_update: true
diff --git a/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml
index a3e65a89f0..d82a942035 100644
--- a/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml
@@ -4,11 +4,12 @@
planning_algorithm: "astar"
waypoints_velocity: 5.0
update_rate: 10.0
- th_arrived_distance_m: 1.0
+ th_arrived_distance_m: 0.5
th_stopped_time_sec: 1.0
th_stopped_velocity_mps: 0.01
th_course_out_distance_m: 1.0
- vehicle_shape_margin_m: 1.0
+ th_obstacle_time_sec: 1.0
+ vehicle_shape_margin_m: 0.5
replan_when_obstacle_found: true
replan_when_course_out: true
@@ -36,9 +37,11 @@
use_back: true
adapt_expansion_distance: true
expansion_distance: 0.5
+ near_goal_distance: 3.0
distance_heuristic_weight: 2.0
smoothness_weight: 0.5
obstacle_distance_weight: 1.75
+ goal_lat_distance_weight: 5.0
# -- RRT* search Configurations --
rrtstar:
diff --git a/autoware_launch/config/system/system_monitor/process_monitor.param.yaml b/autoware_launch/config/system/system_monitor/process_monitor.param.yaml
index 3d6d82fae5..64303dd472 100644
--- a/autoware_launch/config/system/system_monitor/process_monitor.param.yaml
+++ b/autoware_launch/config/system/system_monitor/process_monitor.param.yaml
@@ -1,3 +1,3 @@
/**:
ros__parameters:
- num_of_procs: 5
+ num_of_procs: 40
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index 823b0084b6..5d7b5eb321 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -18,6 +18,7 @@
+
diff --git a/autoware_launch/launch/components/tier4_simulator_component.launch.xml b/autoware_launch/launch/components/tier4_simulator_component.launch.xml
index 817d5d9d97..3bef9b5d1e 100644
--- a/autoware_launch/launch/components/tier4_simulator_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_simulator_component.launch.xml
@@ -2,7 +2,7 @@
-
+
@@ -18,7 +18,7 @@
-
+
@@ -51,7 +51,10 @@
name="object_recognition_tracking_multi_object_tracker_node_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml"
/>
+
+
+
diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml
index eb9373678e..b51b0c0a07 100644
--- a/autoware_launch/launch/planning_simulator.launch.xml
+++ b/autoware_launch/launch/planning_simulator.launch.xml
@@ -37,6 +37,12 @@
+
+
@@ -81,13 +87,12 @@
-
-
+
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index 61e8cf522c..18c391f0db 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -2396,7 +2396,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
- Value: /control/trajectory_follower/lateral/predicted_trajectory
+ Value: /control/trajectory_follower/controller_node_exe/debug/predicted_trajectory_in_frenet_coordinate
Value: true
View Path:
Alpha: 1
@@ -2461,6 +2461,19 @@ Visualization Manager:
Reliability Policy: Reliable
Value: /control/autonomous_emergency_braking/debug/markers
Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: Info/AEB
+ Namespaces:
+ stop_factor_text: true
+ stop_virtual_wall: true
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /control/autonomous_emergency_braking/info/markers
+ Value: true
Enabled: true
Name: Control
- Class: rviz_common/Group