diff --git a/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
similarity index 95%
rename from autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
rename to autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
index 68a42383fe..4233f8b6be 100644
--- a/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
+++ b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
@@ -3,6 +3,7 @@
# Ego path calculation
use_predicted_trajectory: true
use_imu_path: false
+ use_object_velocity_calculation: 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/lane_departure_checker/lane_departure_checker.param.yaml b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml
index 253737609b..3094edf914 100644
--- a/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml
+++ b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml
@@ -16,6 +16,7 @@
# Core
footprint_margin_scale: 1.0
+ footprint_extra_margin: 0.0
resample_interval: 0.3
max_deceleration: 2.8
delay_time: 1.3
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 ec80a0ef79..f62329b8bd 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
@@ -12,6 +12,9 @@
sensor_points:
+ # Tolerance of timestamp difference between current time and sensor pointcloud. [sec]
+ timeout_sec: 1.0
+
# 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
@@ -52,18 +55,21 @@
validation:
- # Tolerance of timestamp difference between current time and sensor pointcloud. [sec]
- lidar_topic_timeout_sec: 1.0
-
# Tolerance of timestamp difference between initial_pose and sensor pointcloud. [sec]
initial_pose_timeout_sec: 1.0
# Tolerance of distance difference between two initial poses used for linear interpolation. [m]
initial_pose_distance_tolerance_m: 10.0
+ # Tolerance of distance difference from initial pose to result pose. [m]
+ initial_to_result_distance_tolerance_m: 3.0
+
# The execution time which means probably NDT cannot matches scans properly. [ms]
critical_upper_bound_exe_time_ms: 100.0
+ # Tolerance for the number of times rejected estimation results consecutively
+ skipping_publish_num: 5
+
score_estimation:
# Converged param type
diff --git a/autoware_launch/config/map/lanelet2_map_loader.param.yaml b/autoware_launch/config/map/lanelet2_map_loader.param.yaml
index b830e038f1..48152605ec 100755
--- a/autoware_launch/config/map/lanelet2_map_loader.param.yaml
+++ b/autoware_launch/config/map/lanelet2_map_loader.param.yaml
@@ -1,4 +1,5 @@
/**:
ros__parameters:
- center_line_resolution: 5.0 # [m]
+ center_line_resolution: 5.0 # [m]
+ use_waypoints: true # "centerline" in the Lanelet2 map will be used as a "waypoints" tag.
lanelet2_map_path: $(var lanelet2_map_path) # The lanelet2 map path
diff --git a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/fusion_common.param.yaml
similarity index 100%
rename from autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml
rename to autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/fusion_common.param.yaml
diff --git a/autoware_launch/config/perception/object_recognition/detection/object_filter/object_lanelet_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_filter/object_lanelet_filter.param.yaml
index dfdee95642..99050d9738 100644
--- a/autoware_launch/config/perception/object_recognition/detection/object_filter/object_lanelet_filter.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/object_filter/object_lanelet_filter.param.yaml
@@ -9,3 +9,13 @@
MOTORCYCLE : false
BICYCLE : false
PEDESTRIAN : false
+
+ filter_settings:
+ # polygon overlap based filter
+ polygon_overlap_filter:
+ enabled: true
+ # velocity direction based filter
+ lanelet_direction_filter:
+ enabled: false
+ velocity_yaw_threshold: 0.785398 # [rad] (45 deg)
+ object_speed_threshold: 3.0 # [m/s]
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 ba1b08abd6..e123b0dda6 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
@@ -1,7 +1,10 @@
/**:
ros__parameters:
enable_delay_compensation: true
- prediction_time_horizon: 10.0 #[s]
+ prediction_time_horizon:
+ vehicle: 15.0 #[s]
+ pedestrian: 10.0 #[s]
+ unknown: 10.0 #[s]
lateral_control_time_horizon: 5.0 #[s]
prediction_sampling_delta_time: 0.5 #[s]
min_velocity_for_map_based_prediction: 1.39 #[m/s]
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
new file mode 100644
index 0000000000..b57f37675d
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/input_channels.param.yaml
@@ -0,0 +1,82 @@
+/**:
+ ros__parameters:
+ input_channels:
+ detected_objects:
+ topic: "/perception/object_recognition/detection/objects"
+ can_spawn_new_tracker: true
+ optional:
+ name: "detected_objects"
+ short_name: "all"
+ # LIDAR - rule-based
+ lidar_clustering:
+ topic: "/perception/object_recognition/detection/clustering/objects"
+ can_spawn_new_tracker: true
+ optional:
+ name: "clustering"
+ short_name: "Lcl"
+ # LIDAR - DNN
+ lidar_centerpoint:
+ topic: "/perception/object_recognition/detection/centerpoint/objects"
+ can_spawn_new_tracker: true
+ optional:
+ name: "centerpoint"
+ short_name: "Lcp"
+ lidar_centerpoint_validated:
+ topic: "/perception/object_recognition/detection/centerpoint/validation/objects"
+ can_spawn_new_tracker: true
+ optional:
+ name: "centerpoint"
+ short_name: "Lcp"
+ lidar_apollo:
+ topic: "/perception/object_recognition/detection/apollo/objects"
+ can_spawn_new_tracker: true
+ optional:
+ name: "apollo"
+ short_name: "Lap"
+ lidar_apollo_validated:
+ topic: "/perception/object_recognition/detection/apollo/validation/objects"
+ can_spawn_new_tracker: true
+ optional:
+ name: "apollo"
+ short_name: "Lap"
+ # LIDAR-CAMERA - DNN
+ # cspell:ignore lidar_pointpainitng pointpainting
+ lidar_pointpainitng:
+ topic: "/perception/object_recognition/detection/pointpainting/objects"
+ can_spawn_new_tracker: true
+ optional:
+ name: "pointpainting"
+ short_name: "Lpp"
+ lidar_pointpainting_validated:
+ topic: "/perception/object_recognition/detection/pointpainting/validation/objects"
+ can_spawn_new_tracker: true
+ optional:
+ name: "pointpainting"
+ short_name: "Lpp"
+ # CAMERA-LIDAR
+ camera_lidar_fusion:
+ topic: "/perception/object_recognition/detection/clustering/camera_lidar_fusion/objects"
+ can_spawn_new_tracker: true
+ optional:
+ name: "camera_lidar_fusion"
+ short_name: "CLf"
+ # CAMERA-LIDAR+TRACKER
+ detection_by_tracker:
+ topic: "/perception/object_recognition/detection/detection_by_tracker/objects"
+ can_spawn_new_tracker: false
+ optional:
+ name: "detection_by_tracker"
+ short_name: "dbT"
+ # RADAR
+ radar:
+ topic: "/sensing/radar/detected_objects"
+ can_spawn_new_tracker: true
+ optional:
+ name: "radar"
+ short_name: "R"
+ radar_far:
+ topic: "/perception/object_recognition/detection/radar/far_objects"
+ can_spawn_new_tracker: true
+ optional:
+ name: "radar_far"
+ short_name: "Rf"
diff --git a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml
index 32a12f8bf5..006c179ae1 100644
--- a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml
@@ -13,11 +13,10 @@
publish_rate: 10.0
world_frame_id: map
enable_delay_compensation: true
- pass_through_unknown_objects: false
- publish_untracked_objects: false
# debug parameters
publish_processing_time: true
publish_tentative_objects: false
+ publish_debug_markers: true
diagnostics_warn_delay: 0.5 # [sec]
diagnostics_error_delay: 1.0 # [sec]
diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml
index 143f11572b..0ffeeeccf0 100644
--- a/autoware_launch/config/planning/preset/default_preset.yaml
+++ b/autoware_launch/config/planning/preset/default_preset.yaml
@@ -1,13 +1,13 @@
launch:
# behavior path modules
- arg:
- name: launch_avoidance_module
+ name: launch_static_obstacle_avoidance
default: "true"
- arg:
name: launch_avoidance_by_lane_change_module
default: "true"
- arg:
- name: launch_dynamic_avoidance_module
+ name: launch_dynamic_obstacle_avoidance
default: "true"
- arg:
name: launch_sampling_planner_module
@@ -74,15 +74,9 @@ launch:
- arg:
name: launch_speed_bump_module
default: "false"
- - arg:
- name: launch_out_of_lane_module
- default: "true"
- arg:
name: launch_no_drivable_lane_module
default: "false"
- - arg:
- name: launch_dynamic_obstacle_stop_module
- default: "true"
# motion planning modules
- arg:
@@ -93,11 +87,22 @@ launch:
- arg:
name: motion_path_planner_type
- default: obstacle_avoidance_planner
- # option: obstacle_avoidance_planner
+ default: path_optimizer
+ # option: path_optimizer
# path_sampler
# none
+ # motion velocity planner modules
+ - arg:
+ name: launch_dynamic_obstacle_stop_module
+ default: "true"
+ - arg:
+ name: launch_out_of_lane_module
+ default: "true"
+ - arg:
+ name: launch_obstacle_velocity_limiter_module
+ default: "true"
+
- arg:
name: motion_stop_planner_type
default: obstacle_cruise_planner
@@ -106,7 +111,7 @@ launch:
# none
- arg:
- name: motion_velocity_smoother_type
+ name: velocity_smoother_type
default: JerkFiltered
# option: JerkFiltered
# L2
diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml b/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/Analytical.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml
rename to autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/Analytical.param.yaml
diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml b/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/JerkFiltered.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml
rename to autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/JerkFiltered.param.yaml
diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/L2.param.yaml b/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/L2.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/L2.param.yaml
rename to autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/L2.param.yaml
diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml b/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/Linf.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml
rename to autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/Linf.param.yaml
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/autoware_velocity_smoother/velocity_smoother.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml
rename to autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/velocity_smoother.param.yaml
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml
rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml
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/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml
similarity index 97%
rename from autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml
rename to 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 dc42af0412..24e88c8ed6 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/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml
@@ -270,7 +270,7 @@
constraints:
# lateral constraints
lateral:
- velocity: [1.0, 1.38, 11.1] # [m/s]
+ velocity: [1.39, 4.17, 11.1] # [m/s]
max_accel_values: [0.5, 0.5, 0.5] # [m/ss]
min_jerk_values: [0.2, 0.2, 0.2] # [m/sss]
max_jerk_values: [1.0, 1.0, 1.0] # [m/sss]
@@ -293,4 +293,11 @@
# for debug
debug:
- marker: false
+ enable_other_objects_marker: false
+ enable_other_objects_info: false
+ enable_detection_area_marker: false
+ enable_drivable_bound_marker: false
+ enable_safety_check_marker: false
+ enable_shift_line_marker: false
+ enable_lane_marker: false
+ enable_misc_marker: false
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 b43179c844..cb1c2b9e30 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
@@ -19,6 +19,7 @@
turn_signal_minimum_search_distance: 10.0
turn_signal_search_time: 3.0
turn_signal_shift_length_threshold: 0.3
+ turn_signal_remaining_shift_length_threshold: 0.1
turn_signal_on_swerving: true
enable_akima_spline_first: false
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 8d4fe057b4..59289d30f5 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
@@ -59,7 +59,7 @@
priority: 1
max_module_size: 1
- avoidance:
+ static_obstacle_avoidance:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
@@ -75,7 +75,7 @@
priority: 3
max_module_size: 1
- dynamic_avoidance:
+ dynamic_obstacle_avoidance:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
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 f2ba29e926..7d64d8c44a 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
@@ -26,7 +26,6 @@
allow_check_shift_path_lane_departure_override: false
shift_collision_check_distance_from_end: -10.0
minimum_shift_pull_out_distance: 0.0
- deceleration_interval: 15.0
maximum_longitudinal_deviation: 1.0 # Note, should be the same or less than planning validator's "longitudinal_distance_deviation"
lateral_jerk: 0.5
lateral_acceleration_sampling_num: 3
@@ -36,10 +35,11 @@
# geometric pull out
enable_geometric_pull_out: true
geometric_collision_check_distance_from_end: 0.0
+ arc_path_interval: 1.0
divide_pull_out_path: true
geometric_pull_out_velocity: 1.0
- arc_path_interval: 1.0
lane_departure_margin: 0.2
+ lane_departure_check_expansion_margin: 0.0
backward_velocity: -1.0
pull_out_max_steer_angle: 0.26 # 15deg
# search start pose backward
@@ -51,9 +51,6 @@
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
# freespace planner
freespace_planner:
enable_freespace_planner: true
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 424029300a..d7131d8c19 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
@@ -3,10 +3,12 @@
blind_spot:
use_pass_judge_line: true
stop_line_margin: 1.0 # [m]
- backward_length: 50.0 # [m]
- ignore_width_from_center_line: 0.0 # [m]
- max_future_movement_time: 10.0 # [second]
- threshold_yaw_diff: 0.523 # [rad]
+ backward_detection_length: 100.0 # [m]
+ ignore_width_from_center_line: 0.7 # [m]
adjacent_extend_width: 1.5 # [m]
opposite_adjacent_extend_width: 1.5 # [m]
- enable_rtc: false # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
+ max_future_movement_time: 10.0 # [second]
+ ttc_min: -5.0 # [s]
+ ttc_max: 5.0 # [s]
+ ttc_ego_minimal_velocity: 5.0 # [m/s]
+ enable_rtc: 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
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/autoware_path_optimizer/path_optimizer.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml
rename to autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/autoware_path_optimizer/path_optimizer.param.yaml
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/motion_planning/motion_velocity_planner/dynamic_obstacle_stop.param.yaml
similarity index 87%
rename from autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml
rename to autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/dynamic_obstacle_stop.param.yaml
index ac95cd75c8..10d749e57a 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/motion_planning/motion_velocity_planner/dynamic_obstacle_stop.param.yaml
@@ -8,5 +8,5 @@
hysteresis: 1.0 # [m] once a collision has been detected, this hysteresis is used on the collision detection
add_stop_duration_buffer : 0.5 # [s] duration where a collision must be continuously detected before a stop decision is added
remove_stop_duration_buffer : 1.0 # [s] duration between no collision being detected and the stop decision being remove
- minimum_object_distance_from_ego_path: 1.0 # [m] minimum distance between the footprints of ego and an object to consider for collision
+ minimum_object_distance_from_ego_trajectory: 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/motion_planning/motion_velocity_planner/motion_velocity_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/motion_velocity_planner.param.yaml
new file mode 100644
index 0000000000..5b2fea537d
--- /dev/null
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/motion_velocity_planner.param.yaml
@@ -0,0 +1,3 @@
+/**:
+ ros__parameters:
+ smooth_velocity_before_planning: true # [-] if true, smooth the velocity profile of the input trajectory before planning
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_velocity_limiter.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml
rename to autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_velocity_limiter.param.yaml
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/motion_planning/motion_velocity_planner/out_of_lane.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml
rename to autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/out_of_lane.param.yaml
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 e9f5833463..42e5ca054a 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
@@ -87,7 +87,8 @@
obstacle_traj_angle_threshold : 1.22 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop
stop:
- max_lat_margin: 0.3 # lateral margin between obstacle and trajectory band with ego's width
+ max_lat_margin: 0.3 # lateral margin between the obstacles and ego's footprint
+ max_lat_margin_against_unknown: 0.3 # lateral margin between the unknown obstacles and ego's footprint
crossing_obstacle:
collision_time_margin : 4.0 # time threshold of collision between obstacle adn ego for cruise or stop [s]
@@ -205,3 +206,15 @@
lpf_gain_slow_down_vel: 0.99 # low-pass filter gain for slow down velocity
lpf_gain_lat_dist: 0.999 # low-pass filter gain for lateral distance from obstacle to ego's path
lpf_gain_dist_to_slow_down: 0.7 # low-pass filter gain for distance to slow down start
+ stop:
+ type_specified_params:
+ labels: # For the listed types, the node try to read the following type specified values
+ - "default"
+ - "unknown"
+ # default: For the default type, which denotes the other types listed above, the following param is defined implicitly, and the other type-specified parameters are not defined.
+ # limit_min_acc: common_param.yaml/limit.min_acc
+ unknown:
+ limit_min_acc: -1.2 # overwrite the deceleration limit, in usually, common_param.yaml/limit.min_acc is referred.
+ sudden_object_acc_threshold: -1.1 # If a stop can be achieved by a deceleration smaller than this value, it is not considered as “sudden stop".
+ sudden_object_dist_threshold: 1000.0 # If a stop distance is longer than this value, it is not considered as “sudden stop".
+ abandon_to_stop: false # If true, the planner gives up to stop when it cannot avoid to run over while maintaining the deceleration limit.
diff --git a/autoware_launch/config/system/component_state_monitor/topics.yaml b/autoware_launch/config/system/component_state_monitor/topics.yaml
index 098aa0e56b..3845a96108 100644
--- a/autoware_launch/config/system/component_state_monitor/topics.yaml
+++ b/autoware_launch/config/system/component_state_monitor/topics.yaml
@@ -4,7 +4,7 @@
args:
node_name_suffix: vector_map
topic: /map/vector_map
- topic_type: autoware_auto_mapping_msgs/msg/HADMapBin
+ topic_type: autoware_map_msgs/msg/LaneletMapBin
best_effort: false
transient_local: true
warn_rate: 0.0
@@ -69,7 +69,7 @@
args:
node_name_suffix: object_recognition_objects
topic: /perception/object_recognition/objects
- topic_type: autoware_auto_perception_msgs/msg/PredictedObjects
+ topic_type: autoware_perception_msgs/msg/PredictedObjects
best_effort: false
transient_local: false
warn_rate: 5.0
@@ -82,7 +82,7 @@
args:
node_name_suffix: traffic_light_recognition_traffic_signals
topic: /perception/traffic_light_recognition/traffic_signals
- topic_type: autoware_perception_msgs/msg/TrafficSignalArray
+ topic_type: autoware_perception_msgs/msg/TrafficLightGroupArray
best_effort: false
transient_local: false
warn_rate: 5.0
@@ -108,7 +108,7 @@
args:
node_name_suffix: scenario_planning_trajectory
topic: /planning/scenario_planning/trajectory
- topic_type: autoware_auto_planning_msgs/msg/Trajectory
+ topic_type: autoware_planning_msgs/msg/Trajectory
best_effort: false
transient_local: false
warn_rate: 5.0
@@ -121,7 +121,7 @@
args:
node_name_suffix: trajectory_follower_control_cmd
topic: /control/trajectory_follower/control_cmd
- topic_type: autoware_auto_control_msgs/msg/AckermannControlCommand
+ topic_type: autoware_control_msgs/msg/Control
best_effort: false
transient_local: false
warn_rate: 5.0
@@ -134,7 +134,7 @@
args:
node_name_suffix: control_command_control_cmd
topic: /control/command/control_cmd
- topic_type: autoware_auto_control_msgs/msg/AckermannControlCommand
+ topic_type: autoware_control_msgs/msg/Control
best_effort: false
transient_local: false
warn_rate: 5.0
@@ -147,7 +147,7 @@
args:
node_name_suffix: vehicle_status_velocity_status
topic: /vehicle/status/velocity_status
- topic_type: autoware_auto_vehicle_msgs/msg/VelocityReport
+ topic_type: autoware_vehicle_msgs/msg/VelocityReport
best_effort: false
transient_local: false
warn_rate: 5.0
@@ -160,7 +160,7 @@
args:
node_name_suffix: vehicle_status_steering_status
topic: /vehicle/status/steering_status
- topic_type: autoware_auto_vehicle_msgs/msg/SteeringReport
+ topic_type: autoware_vehicle_msgs/msg/SteeringReport
best_effort: false
transient_local: false
warn_rate: 5.0
@@ -173,7 +173,7 @@
args:
node_name_suffix: system_emergency_control_cmd
topic: /system/emergency/control_cmd
- topic_type: autoware_auto_control_msgs/msg/AckermannControlCommand
+ topic_type: autoware_control_msgs/msg/Control
best_effort: false
transient_local: false
warn_rate: 5.0
diff --git a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-awsim.yaml b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-awsim.yaml
new file mode 100644
index 0000000000..9950acbc7e
--- /dev/null
+++ b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-awsim.yaml
@@ -0,0 +1,5 @@
+files:
+ - { path: $(find-pkg-share system_diagnostic_monitor)/config/autoware-main.yaml }
+
+edits:
+ - { type: remove, path: /autoware/system/duplicated_node_checker }
diff --git a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-main.yaml b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-main.yaml
new file mode 100644
index 0000000000..42af3f79a3
--- /dev/null
+++ b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-main.yaml
@@ -0,0 +1,2 @@
+files:
+ - { path: $(find-pkg-share system_diagnostic_monitor)/config/autoware-main.yaml }
diff --git a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml
new file mode 100644
index 0000000000..dfc820f93c
--- /dev/null
+++ b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml
@@ -0,0 +1,2 @@
+files:
+ - { path: $(find-pkg-share system_diagnostic_monitor)/config/autoware-psim.yaml }
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 8210c7db23..9710e1a1e4 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
@@ -35,6 +35,7 @@
/autoware/planning/performance_monitoring/trajectory_validation: default
# /autoware/sensing/node_alive_monitoring: default
+ # /autoware/control/autoware_autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false", ignore_until_waiting_for_route: "true"}
/autoware/system/node_alive_monitoring: default
/autoware/system/emergency_stop_operation: 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 af8ec0da30..c1821a05ab 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
@@ -35,6 +35,7 @@
/autoware/planning/performance_monitoring/trajectory_validation: default
# /autoware/sensing/node_alive_monitoring: default
+ # /autoware/control/autoware_autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false", ignore_until_waiting_for_route: "true"}
/autoware/system/node_alive_monitoring: default
/autoware/system/emergency_stop_operation: default
diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml
index 7a219a4c89..8b76c48ac7 100644
--- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml
+++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml
@@ -25,7 +25,7 @@
/autoware/localization/node_alive_monitoring: default
# /autoware/localization/performance_monitoring/scan_matching_status: { sf_at: "warn", lf_at: "none", spf_at: "none" }
# /autoware/localization/performance_monitoring/localization_error_ellipse: default
-
+ # /autoware/control/autoware_autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false", ignore_until_waiting_for_route: "true"}
/autoware/map/node_alive_monitoring: default
/autoware/perception/node_alive_monitoring: default
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 aa76152e57..c11af361f3 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,8 +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
+ csv_path_accel_map: $(find-pkg-share autoware_raw_vehicle_cmd_converter)/data/default/accel_map.csv
+ csv_path_brake_map: $(find-pkg-share autoware_raw_vehicle_cmd_converter)/data/default/brake_map.csv
+ csv_path_steer_map: $(find-pkg-share autoware_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/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index 3d713f3716..38f8550f72 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -37,6 +37,7 @@
+
diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml
index cf5c333dc4..09b817b149 100644
--- a/autoware_launch/launch/components/tier4_control_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_control_component.launch.xml
@@ -39,7 +39,7 @@
-
+
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index 8418afabdf..e13b987607 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -49,7 +49,7 @@
/>
+
-
+
-
+
@@ -37,7 +43,7 @@
-
+
@@ -51,9 +57,7 @@
-
-
@@ -62,17 +66,24 @@
-
+
-
+
+
+
+
+
-
-
+
+
diff --git a/autoware_launch/launch/components/tier4_simulator_component.launch.xml b/autoware_launch/launch/components/tier4_simulator_component.launch.xml
index c2f2b7ca92..a0eb99c7a7 100644
--- a/autoware_launch/launch/components/tier4_simulator_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_simulator_component.launch.xml
@@ -41,6 +41,10 @@
name="object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml"
/>
+
+
+
@@ -27,10 +29,9 @@
-
+
-
-
-
+
+
diff --git a/autoware_launch/launch/e2e_simulator.launch.xml b/autoware_launch/launch/e2e_simulator.launch.xml
index 902d9bc33c..d05d0acb62 100644
--- a/autoware_launch/launch/e2e_simulator.launch.xml
+++ b/autoware_launch/launch/e2e_simulator.launch.xml
@@ -6,6 +6,7 @@
+
@@ -39,6 +40,9 @@
+
+
+
@@ -68,6 +72,7 @@
+
diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml
index 77d17d7897..8780578a6e 100644
--- a/autoware_launch/launch/logging_simulator.launch.xml
+++ b/autoware_launch/launch/logging_simulator.launch.xml
@@ -63,6 +63,7 @@
+
diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml
index b389abf61c..d038e7096b 100644
--- a/autoware_launch/launch/planning_simulator.launch.xml
+++ b/autoware_launch/launch/planning_simulator.launch.xml
@@ -61,6 +61,7 @@
+
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index 40db36a916..61e8cf522c 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -5,7 +5,7 @@ Panels:
Property Tree Widget:
Expanded: ~
Splitter Ratio: 0.557669460773468
- Tree Height: 397
+ Tree Height: 185
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
@@ -77,62 +77,62 @@ Visualization Manager:
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera0/camera_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera0/camera_optical_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
camera1/camera_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera1/camera_optical_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
camera2/camera_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera2/camera_optical_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
camera3/camera_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera3/camera_optical_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
camera4/camera_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera4/camera_optical_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
camera5/camera_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera5/camera_optical_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
gnss_link:
@@ -159,69 +159,69 @@ Visualization Manager:
Show Trail: false
Value: true
sensor_kit_base_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
tamagawa/imu_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
traffic_light_left_camera/camera_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
traffic_light_left_camera/camera_optical_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
traffic_light_right_camera/camera_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
traffic_light_right_camera/camera_optical_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
velodyne_left:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
velodyne_left_base_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
velodyne_rear:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
velodyne_rear_base_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
velodyne_right:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
velodyne_right_base_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
velodyne_top:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
velodyne_top_base_link:
- Alpha: 0.999
+ Alpha: 1
Show Axes: false
Show Trail: false
Value: true
@@ -408,7 +408,7 @@ Visualization Manager:
Name: LiDAR
- Class: rviz_common/Group
Displays:
- - Alpha: 0.9990000128746033
+ - Alpha: 0.999
Axes Length: 1
Axes Radius: 0.10000000149011612
Class: rviz_default_plugins/PoseWithCovariance
@@ -687,7 +687,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.999
Color: 119; 11; 32
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display 3d polygon: true
Display Label: true
Display PoseWithCovariance: true
@@ -735,7 +735,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.999
Color: 119; 11; 32
- Class: autoware_auto_perception_rviz_plugin/TrackedObjects
+ Class: autoware_perception_rviz_plugin/TrackedObjects
Display 3d polygon: true
Display Label: true
Display PoseWithCovariance: true
@@ -783,7 +783,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.999
Color: 119; 11; 32
- Class: autoware_auto_perception_rviz_plugin/PredictedObjects
+ Class: autoware_perception_rviz_plugin/PredictedObjects
Display 3d polygon: true
Display Label: true
Display PoseWithCovariance: false
@@ -936,6 +936,7 @@ Visualization Manager:
Top: 10
Remaining Distance and Time Topic: /planning/mission_remaining_distance_time
Enabled: true
+ Value: true
Enabled: true
Name: MissionPlanning
- Class: rviz_common/Group
@@ -1022,7 +1023,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
- Value: /planning/path_reference/avoidance
+ Value: /planning/path_reference/static_obstacle_avoidance
Value: true
View Path:
Alpha: 0.3
@@ -1275,7 +1276,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
- Value: /planning/path_candidate/avoidance
+ Value: /planning/path_candidate/static_obstacle_avoidance
Value: true
View Path:
Alpha: 0.30000001192092896
@@ -1353,7 +1354,7 @@ Visualization Manager:
Displays:
- Class: rviz_default_plugins/MarkerArray
Enabled: true
- Name: VirtualWall (Avoidance)
+ Name: VirtualWall (StaticObstacleAvoidance)
Namespaces:
{}
Topic:
@@ -1361,7 +1362,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
- Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/avoidance
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/static_obstacle_avoidance
Value: true
- Class: rviz_default_plugins/MarkerArray
Enabled: true
@@ -1604,18 +1605,6 @@ Visualization Manager:
Reliability Policy: Reliable
Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/speed_bump
Value: true
- - Class: rviz_default_plugins/MarkerArray
- Enabled: true
- Name: VirtualWall (OutOfLane)
- Namespaces:
- {}
- Topic:
- Depth: 5
- Durability Policy: Volatile
- History Policy: Keep Last
- Reliability Policy: Reliable
- Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/out_of_lane
- Value: true
- Class: rviz_default_plugins/MarkerArray
Enabled: true
Name: VirtualWall (NoDrivableLane)
@@ -1628,18 +1617,6 @@ Visualization Manager:
Reliability Policy: Reliable
Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/no_drivable_lane
Value: true
- - Class: rviz_default_plugins/MarkerArray
- Enabled: true
- Name: VirtualWall (DynamicObstacleStop)
- Namespaces:
- {}
- Topic:
- Depth: 5
- Durability Policy: Volatile
- History Policy: Keep Last
- Reliability Policy: Reliable
- Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/dynamic_obstacle_stop
- Value: true
Enabled: true
Name: VirtualWall
- Class: rviz_common/Group
@@ -1778,7 +1755,7 @@ Visualization Manager:
Value: false
- Class: rviz_default_plugins/MarkerArray
Enabled: false
- Name: Avoidance
+ Name: StaticObstacleAvoidance
Namespaces:
{}
Topic:
@@ -1786,7 +1763,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
- Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/static_obstacle_avoidance
Value: false
- Class: rviz_default_plugins/MarkerArray
Enabled: false
@@ -1874,19 +1851,7 @@ Visualization Manager:
Value: false
- Class: rviz_default_plugins/MarkerArray
Enabled: false
- Name: OutOfLane
- Namespaces:
- {}
- Topic:
- Depth: 5
- Durability Policy: Volatile
- History Policy: Keep Last
- Reliability Policy: Reliable
- Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/out_of_lane
- Value: false
- - Class: rviz_default_plugins/MarkerArray
- Enabled: false
- Name: DynamicAvoidance
+ Name: DynamicObstacleAvoidance
Namespaces:
{}
Topic:
@@ -1894,7 +1859,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
- Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/dynamic_avoidance
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/dynamic_obstacle_avoidance
Value: false
- Class: rviz_default_plugins/MarkerArray
Enabled: false
@@ -1908,25 +1873,13 @@ Visualization Manager:
Reliability Policy: Reliable
Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_drivable_lane
Value: false
- - Class: rviz_default_plugins/MarkerArray
- Enabled: false
- Name: DynamicObstacleStop
- Namespaces:
- {}
- Topic:
- Depth: 5
- Durability Policy: Volatile
- History Policy: Keep Last
- Reliability Policy: Reliable
- Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/dynamic_obstacle_stop
- Value: false
Enabled: false
Name: DebugMarker
- Class: rviz_common/Group
Displays:
- Class: rviz_default_plugins/MarkerArray
Enabled: false
- Name: Info (Avoidance)
+ Name: Info (StaticObstacleAvoidance)
Namespaces:
avoidable_target_objects_info: false
avoidable_target_objects_info_reason: false
@@ -1939,7 +1892,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
- Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/avoidance
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/static_obstacle_avoidance
Value: false
- Class: rviz_default_plugins/MarkerArray
Enabled: false
@@ -2027,7 +1980,7 @@ Visualization Manager:
Value: false
- Class: rviz_default_plugins/MarkerArray
Enabled: false
- Name: Info (DynamicAvoidance)
+ Name: Info (DynamicObstacleAvoidance)
Namespaces:
{}
Topic:
@@ -2035,7 +1988,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
- Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/dynamic_avoidance
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/dynamic_obstacle_avoidance
Value: false
Enabled: false
Name: InfoMarker
@@ -2126,7 +2079,43 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
- Value: /planning/scenario_planning/motion_velocity_smoother/virtual_wall
+ Value: /planning/scenario_planning/velocity_smoother/virtual_wall
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (OutOfLane)
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/out_of_lane/virtual_walls
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (ObstacleVelocityLimiter)
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_velocity_limiter/virtual_walls
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (DynamicObstacleStop)
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/dynamic_obstacle_stop/virtual_walls
Value: true
Enabled: true
Name: VirtualWall
@@ -2251,6 +2240,46 @@ Visualization Manager:
Reliability Policy: Reliable
Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker
Value: false
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: OutOfLane
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/out_of_lane/debug_markers
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: ObstacleVelocityLimiter
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_velocity_limiter/debug_markers
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: DynamicObstacleStop
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/dynamic_obstacle_stop/debug_markers
+ Value: true
+ Enabled: false
+ Name: MotionVelocityPlanner
Enabled: false
Name: DebugMarker
Enabled: true
@@ -2488,7 +2517,6 @@ Visualization Manager:
Planning: true
Sensing:
ConcatenatePointCloud: true
- PointcloudOnCamera: true
RadarRawObjects(white): true
Value: true
Value: true
@@ -2539,6 +2567,7 @@ Visualization Manager:
Value: true
MissionPlanning:
GoalPose: true
+ MissionDetailsDisplay: true
RouteArea: true
Value: true
ScenarioPlanning:
@@ -2548,11 +2577,11 @@ Visualization Manager:
Bound: true
DebugMarker:
Arrow: true
- Avoidance: true
+ StaticObstacleAvoidance: true
Blind Spot: true
Crosswalk: true
DetectionArea: true
- DynamicAvoidance: true
+ DynamicObstacleAvoidance: true
GoalPlanner: true
Intersection: true
LaneFollowing: true
@@ -2560,7 +2589,6 @@ Visualization Manager:
NoDrivableLane: true
NoStoppingArea: true
OcclusionSpot: true
- OutOfLane: true
RightLaneChange: true
RunOut: true
SideShift: true
@@ -2571,9 +2599,9 @@ Visualization Manager:
Value: true
VirtualTrafficLight: true
InfoMarker:
- Info (Avoidance): true
+ Info (StaticObstacleAvoidance): true
Info (AvoidanceByLC): true
- Info (DynamicAvoidance): true
+ Info (DynamicObstacleAvoidance): true
Info (ExtLaneChangeLeft): true
Info (ExtLaneChangeRight): true
Info (GoalPlanner): true
@@ -2599,7 +2627,7 @@ Visualization Manager:
Value: true
VirtualWall:
Value: true
- VirtualWall (Avoidance): true
+ VirtualWall (StaticObstacleAvoidance): true
VirtualWall (AvoidanceByLC): true
VirtualWall (BlindSpot): true
VirtualWall (Crosswalk): true
@@ -2614,7 +2642,6 @@ Visualization Manager:
VirtualWall (NoDrivableLane): true
VirtualWall (NoStoppingArea): true
VirtualWall (OcclusionSpot): true
- VirtualWall (OutOfLane): true
VirtualWall (RunOut): true
VirtualWall (SpeedBump): true
VirtualWall (StartPlanner): true
@@ -2720,7 +2747,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.5
Color: 255; 255; 255
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -2877,7 +2904,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 255; 138; 128
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -2924,7 +2951,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 255; 82; 82
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -2971,7 +2998,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 213; 0; 0
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -3018,7 +3045,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 178; 255; 89
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -3065,7 +3092,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 118; 255; 3
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -3112,7 +3139,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 100; 221; 23
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -3159,7 +3186,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 255; 145; 0
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -3206,7 +3233,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 213; 0; 249
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -3253,7 +3280,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 255; 255; 255
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -3300,7 +3327,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 255; 234; 0
- Class: autoware_auto_perception_rviz_plugin/DetectedObjects
+ Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -3347,7 +3374,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 0; 230; 118
- Class: autoware_auto_perception_rviz_plugin/TrackedObjects
+ Class: autoware_perception_rviz_plugin/TrackedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
@@ -3394,7 +3421,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.9990000128746033
Color: 0; 176; 255
- Class: autoware_auto_perception_rviz_plugin/PredictedObjects
+ Class: autoware_perception_rviz_plugin/PredictedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: false
@@ -3472,7 +3499,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
- Value: /planning/debug/objects_of_interest/avoidance_left
+ Value: /planning/debug/objects_of_interest/static_obstacle_avoidance_left
Value: true
- Class: rviz_default_plugins/MarkerArray
Enabled: true
@@ -3484,7 +3511,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
- Value: /planning/debug/objects_of_interest/avoidance_right
+ Value: /planning/debug/objects_of_interest/static_obstacle_avoidance_right
Value: true
- Class: rviz_default_plugins/MarkerArray
Enabled: true
@@ -3608,22 +3635,6 @@ Visualization Manager:
Value: true
Enabled: true
Name: Objects Of Interest
- - Class: rviz_plugins/StringStampedOverlayDisplay
- Enabled: true
- Font Size: 15
- Left: 1024
- Max Letter Num: 100
- Name: StringStampedOverlayDisplay
- Text Color: 25; 255; 240
- Top: 128
- Topic:
- Depth: 5
- Durability Policy: Volatile
- History Policy: Keep Last
- Reliability Policy: Reliable
- Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/internal_state
- Value: true
- Value height offset: 0
Enabled: true
Name: Planning
- Class: rviz_common/Group
@@ -3767,7 +3778,7 @@ Window Geometry:
Hide Right Dock: false
Image:
collapsed: false
- QMainWindow State: 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
+ QMainWindow State: 000000ff00000000fd0000000400000000000001ee00000368fc020000000efb0000001200530065006c0065006300740069006f006e00000001e10000009b0000008900fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb00000024004100750074006f00770061007200650053007400610074006500500061006e0065006c0100000057000002740000007b00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000682000000eb0000000000000000fb0000000a0049006d0061006700650100000505000002680000000000000000fb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000000000000000fb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000000000000000fb00000030005200650063006f0067006e006900740069006f006e0052006500730075006c0074004f006e0049006d00610067006501000002cf000000f00000004500fffffffb0000002a004100750074006f0077006100720065004400610074006500540069006d006500500061006e0065006c0000000332000000720000006900fffffffb000000240050006f0069006e00740063006c006f00750064004f006e00430061006d006500720061000000039d000000560000004500ffffff00000001000001ab00000368fc0200000004fb000000100044006900730070006c00610079007301000000570000012e0000012500fffffffc0000018900000236000001050100001dfa000000000100000002fb0000000a0056006900650077007301000005d5000001ab000001ab00fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000000ffffffff0000009000fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000e7a0000005afc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000e7a0000005afc0100000002fb0000000800540069006d0065010000000000000e7a0000000000000000fb0000000800540069006d00650100000000000004500000000000000000000003df0000036800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
RecognitionResultOnImage:
collapsed: false
Selection: