diff --git a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
index 97a1d64ed8..5c5d65a13b 100644
--- a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
+++ b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
@@ -60,6 +60,10 @@
emergency_acc: -5.0 # denotes acceleration
emergency_jerk: -3.0
+ # acceleration feedback
+ lpf_acc_error_gain: 0.98
+ acc_feedback_gain: 0.0
+
# acceleration limit
max_acc: 3.0
min_acc: -5.0
diff --git a/autoware_launch/config/localization/ekf_localizer.param.yaml b/autoware_launch/config/localization/ekf_localizer.param.yaml
index 4a7696ec9e..13319521e3 100644
--- a/autoware_launch/config/localization/ekf_localizer.param.yaml
+++ b/autoware_launch/config/localization/ekf_localizer.param.yaml
@@ -30,8 +30,8 @@
simple_1d_filter_parameters:
#Simple1DFilter parameters
z_filter_proc_dev: 1.0
- roll_filter_proc_dev: 0.01
- pitch_filter_proc_dev: 0.01
+ roll_filter_proc_dev: 0.1
+ pitch_filter_proc_dev: 0.1
diagnostics:
# for diagnostics
diff --git a/autoware_launch/config/localization/lidar_marker_localizer/lidar_marker_localizer.param.yaml b/autoware_launch/config/localization/lidar_marker_localizer/lidar_marker_localizer.param.yaml
new file mode 100644
index 0000000000..1c04d51e5d
--- /dev/null
+++ b/autoware_launch/config/localization/lidar_marker_localizer/lidar_marker_localizer.param.yaml
@@ -0,0 +1,42 @@
+/**:
+ ros__parameters:
+
+ # marker name
+ marker_name: "reflector"
+
+ # for marker detection algorithm
+ resolution: 0.05
+ # A sequence of high/low intensity to perform pattern matching.
+ # 1: high intensity (positive match), 0: not consider, -1: low intensity (negative match)
+ intensity_pattern: [-1, -1, 0, 1, 1, 1, 1, 1, 0, -1, -1]
+ match_intensity_difference_threshold: 20
+ positive_match_num_threshold: 3
+ negative_match_num_threshold: 3
+ vote_threshold_for_detect_marker: 20
+ marker_height_from_ground: 1.075
+
+ # for interpolate algorithm
+ self_pose_timeout_sec: 1.0
+ self_pose_distance_tolerance_m: 1.0
+
+ # for validation
+ limit_distance_from_self_pose_to_nearest_marker: 2.0
+ limit_distance_from_self_pose_to_marker: 2.0
+
+ # base_covariance
+ # [TBD] This value is dynamically scaled according to the distance at which markers are detected.
+ base_covariance: [0.04, 0.0, 0.0, 0.0, 0.0, 0.0,
+ 0.0, 0.04, 0.0, 0.0, 0.0, 0.0,
+ 0.0, 0.0, 0.01, 0.0, 0.0, 0.0,
+ 0.0, 0.0, 0.0, 0.00007569, 0.0, 0.0,
+ 0.0, 0.0, 0.0, 0.0, 0.00007569, 0.0,
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.00030625]
+
+ # for visualize the detected marker pointcloud
+ marker_width: 0.8
+
+ # for save log
+ enable_save_log: false
+ save_file_directory_path: detected_reflector_intensity
+ save_file_name: detected_reflector_intensity
+ save_frame_id: velodyne_top
diff --git a/autoware_launch/config/localization/lidar_marker_localizer/pointcloud_preprocessor/crop_box_filter_measurement_range.param.yaml b/autoware_launch/config/localization/lidar_marker_localizer/pointcloud_preprocessor/crop_box_filter_measurement_range.param.yaml
new file mode 100644
index 0000000000..6b3986540d
--- /dev/null
+++ b/autoware_launch/config/localization/lidar_marker_localizer/pointcloud_preprocessor/crop_box_filter_measurement_range.param.yaml
@@ -0,0 +1,11 @@
+/**:
+ ros__parameters:
+ input_frame: "base_link"
+ output_frame: "base_link"
+ min_x: -10.0
+ max_x: 10.0
+ min_y: 0.0
+ max_y: 7.5
+ min_z: -5.0
+ max_z: 5.0
+ negative: False
diff --git a/autoware_launch/config/localization/lidar_marker_localizer/pointcloud_preprocessor/ring_filter.param.yaml b/autoware_launch/config/localization/lidar_marker_localizer/pointcloud_preprocessor/ring_filter.param.yaml
new file mode 100644
index 0000000000..7d87f797c1
--- /dev/null
+++ b/autoware_launch/config/localization/lidar_marker_localizer/pointcloud_preprocessor/ring_filter.param.yaml
@@ -0,0 +1,9 @@
+/**:
+ ros__parameters:
+ input_frame: "base_link"
+ output_frame: "base_link"
+ filter_field_name: "channel"
+ filter_limit_min: 5
+ filter_limit_max: 45
+ filter_limit_negative: False
+ keep_organized: False
diff --git a/autoware_launch/config/localization/stop_filter.param.yaml b/autoware_launch/config/localization/stop_filter.param.yaml
new file mode 100644
index 0000000000..ded090b75b
--- /dev/null
+++ b/autoware_launch/config/localization/stop_filter.param.yaml
@@ -0,0 +1,4 @@
+/**:
+ ros__parameters:
+ vx_threshold: 0.1 # [m/s]
+ wz_threshold: 0.02 # [rad/s]
diff --git a/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/object_lanelet_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/object_lanelet_filter.param.yaml
new file mode 100644
index 0000000000..99050d9738
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/object_lanelet_filter.param.yaml
@@ -0,0 +1,21 @@
+/**:
+ ros__parameters:
+ filter_target_label:
+ UNKNOWN : true
+ CAR : false
+ TRUCK : false
+ BUS : false
+ TRAILER : false
+ 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/detection/detected_object_validation/object_position_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/object_position_filter.param.yaml
new file mode 100644
index 0000000000..70afd9d31b
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/object_position_filter.param.yaml
@@ -0,0 +1,16 @@
+/**:
+ ros__parameters:
+ filter_target_label:
+ UNKNOWN : true
+ CAR : false
+ TRUCK : false
+ BUS : false
+ TRAILER : false
+ MOTORCYCLE : false
+ BICYCLE : false
+ PEDESTRIAN : false
+
+ upper_bound_x: 100.0
+ lower_bound_x: 0.0
+ upper_bound_y: 10.0
+ lower_bound_y: -10.0
diff --git a/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml
index b98f8adfb5..c0a437a125 100644
--- a/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml
@@ -2,14 +2,15 @@
ros__parameters:
min_points_num:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
- [10, 10, 10, 10, 10,10, 10, 10]
+ [10, 10, 10, 10, 10, 10, 10, 10]
max_points_num:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
- [10, 10, 10, 10, 10,10, 10, 10]
+ [10, 10, 10, 10, 10, 10, 10, 10]
min_points_and_distance_ratio:
- #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
- [800.0, 880.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0]
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0]
using_2d_validator: true
+ enable_debugger: false
diff --git a/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/occupancy_grid_based_validator.param.yaml b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/occupancy_grid_based_validator.param.yaml
new file mode 100644
index 0000000000..bb996f1197
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/occupancy_grid_based_validator.param.yaml
@@ -0,0 +1,4 @@
+/**:
+ ros__parameters:
+ mean_threshold: 0.6
+ enable_debug: false
diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/transfusion.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/transfusion.param.yaml
new file mode 100644
index 0000000000..47eaa800e6
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/transfusion.param.yaml
@@ -0,0 +1,17 @@
+/**:
+ ros__parameters:
+ # network
+ trt_precision: fp16
+ cloud_capacity: 2000000
+ onnx_path: "$(var model_path)/transfusion.onnx"
+ engine_path: "$(var model_path)/transfusion.engine"
+ # pre-process params
+ densification_num_past_frames: 1
+ densification_world_frame_id: map
+ # 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] # refers to the class_names
+ score_threshold: 0.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 5d68825f4d..9034ff65b2 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
@@ -7,7 +7,7 @@
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]
+ min_velocity_for_map_based_prediction: 1.0 #[m/s]
min_crosswalk_user_velocity: 1.39 #[m/s]
max_crosswalk_user_delta_yaw_threshold_for_lanelet: 0.785 #[m/s]
dist_threshold_for_searching_lanelet: 3.0 #[m]
diff --git a/autoware_launch/config/perception/obstacle_segmentation/occupancy_grid_based_outlier_filter/occupancy_grid_map_outlier_filter.param.yaml b/autoware_launch/config/perception/obstacle_segmentation/occupancy_grid_based_outlier_filter/occupancy_grid_map_outlier_filter.param.yaml
new file mode 100644
index 0000000000..61cd3a2dc1
--- /dev/null
+++ b/autoware_launch/config/perception/obstacle_segmentation/occupancy_grid_based_outlier_filter/occupancy_grid_map_outlier_filter.param.yaml
@@ -0,0 +1,12 @@
+/**:
+ ros__parameters:
+ radius_search_2d_filter.search_radius: 1.0
+ radius_search_2d_filter.min_points_and_distance_ratio: 400.0
+ radius_search_2d_filter.min_points: 4
+ radius_search_2d_filter.max_points: 70
+ radius_search_2d_filter.max_filter_points_nb: 15000
+ map_frame: "map"
+ base_link_frame: "base_link"
+ cost_threshold: 45
+ use_radius_search_2d_filter: true
+ enable_debugger: false
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 497c0eef02..31e35dcad5 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
@@ -23,44 +23,44 @@
th_moving_time: 2.0 # [s]
longitudinal_margin: 0.0 # [m]
lateral_margin:
- soft_margin: 0.3 # [m]
+ soft_margin: 0.7 # [m]
hard_margin: 0.2 # [m]
hard_margin_for_parked_vehicle: 0.7 # [m]
max_expand_ratio: 0.0 # [-] FOR DEVELOPER
- envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER
+ envelope_buffer_margin: 0.1 # [m] FOR DEVELOPER
th_error_eclipse_long_radius : 0.6 # [m]
truck:
th_moving_speed: 1.0
th_moving_time: 2.0
longitudinal_margin: 0.0
lateral_margin:
- soft_margin: 0.3
+ soft_margin: 0.7
hard_margin: 0.2
hard_margin_for_parked_vehicle: 0.7
max_expand_ratio: 0.0
- envelope_buffer_margin: 0.5
+ envelope_buffer_margin: 0.1
th_error_eclipse_long_radius : 0.6
bus:
th_moving_speed: 1.0
th_moving_time: 2.0
longitudinal_margin: 0.0
lateral_margin:
- soft_margin: 0.3
+ soft_margin: 0.7
hard_margin: 0.2
hard_margin_for_parked_vehicle: 0.7
max_expand_ratio: 0.0
- envelope_buffer_margin: 0.5
+ envelope_buffer_margin: 0.1
th_error_eclipse_long_radius : 0.6
trailer:
th_moving_speed: 1.0
th_moving_time: 2.0
longitudinal_margin: 0.0
lateral_margin:
- soft_margin: 0.3
+ soft_margin: 0.7
hard_margin: 0.2
hard_margin_for_parked_vehicle: 0.7
max_expand_ratio: 0.0
- envelope_buffer_margin: 0.5
+ envelope_buffer_margin: 0.1
th_error_eclipse_long_radius : 0.6
unknown:
th_moving_speed: 0.28
@@ -232,7 +232,7 @@
# avoidance distance parameters
longitudinal:
min_prepare_time: 1.0 # [s]
- max_prepare_time: 2.0 # [s]
+ max_prepare_time: 3.0 # [s]
min_prepare_distance: 1.0 # [m]
min_slow_down_speed: 1.38 # [m/s]
buf_slow_down_speed: 0.56 # [m/s] FOR DEVELOPER
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_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
index 97cf050f18..150478ce26 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_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
@@ -1,34 +1,24 @@
/**:
ros__parameters:
out_of_lane: # module to stop or slowdown before overlapping another lane with other objects
- mode: ttc # mode used to consider a conflict with an object. "threshold", "intervals", or "ttc"
+ mode: ttc # mode used to consider a conflict with an object. "threshold", or "ttc"
skip_if_already_overlapping: false # do not run this module when ego already overlaps another lane
ignore_overlaps_over_lane_changeable_lanelets: true # if true, overlaps on lane changeable lanelets are ignored
+ max_arc_length: 100.0 # [m] maximum trajectory arc length that is checked for out_of_lane collisions
threshold:
time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time
- intervals: # consider objects if their estimated time interval spent on the overlap intersect the estimated time interval of ego
- ego_time_buffer: 0.5 # [s] extend the ego time interval by this buffer
- objects_time_buffer: 0.5 # [s] extend the time intervals of objects by this buffer
ttc:
- threshold: 3.0 # [s] consider objects with an estimated time to collision bellow this value while on the overlap
+ threshold: 1.0 # [s] consider objects with an estimated time to collision bellow this value while on the overlap
objects:
minimum_velocity: 0.5 # [m/s] objects lower than this velocity will be ignored
- use_predicted_paths: true # if true, use the predicted paths to estimate future positions.
- # if false, assume the object moves at constant velocity along *all* lanelets it currently is located in.
predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value.
- distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane
cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights
ignore_behind_ego: false # if true, objects behind the ego vehicle are ignored
- overlap:
- minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered
- extra_length: 0.0 # [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times)
-
- action: # action to insert in the path if an object causes a conflict at an overlap
- skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed
- precision: 0.1 # [m] precision when inserting a stop pose in the path
+ action: # action to insert in the trajectory if an object causes a conflict at an overlap
+ precision: 0.1 # [m] precision when inserting a stop pose in the trajectory
longitudinal_distance_buffer: 1.5 # [m] safety distance buffer to keep in front of the ego vehicle
lateral_distance_buffer: 1.0 # [m] safety distance buffer to keep on the side of the ego vehicle
min_duration: 1.0 # [s] minimum duration needed before a decision can be canceled
@@ -39,8 +29,8 @@
distance_threshold: 15.0 # [m] insert a stop when closer than this distance from an overlap
ego:
- min_assumed_velocity: 2.0 # [m/s] minimum velocity used to calculate the enter and exit times of ego
- extra_front_offset: 0.0 # [m] extra front distance
- extra_rear_offset: 0.0 # [m] extra rear distance
- extra_right_offset: 0.0 # [m] extra right distance
- extra_left_offset: 0.0 # [m] extra left distance
+ # extra footprint offsets to calculate out of lane collisions
+ extra_front_offset: 0.0 # [m] extra footprint front distance
+ extra_rear_offset: 0.0 # [m] extra footprint rear distance
+ extra_right_offset: 0.0 # [m] extra footprint right distance
+ extra_left_offset: 0.0 # [m] extra footprint left distance
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 c11af361f3..e108de527e 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
@@ -26,3 +26,8 @@
max_d: 0.0
min_d: 0.0
invalid_integration_decay: 0.97
+ convert_steer_cmd_method: "vgr" # "vgr" or "steer_map"
+ vgr_coef_a: 15.713
+ vgr_coef_b: 0.053
+ vgr_coef_c: 0.042
+ convert_actuation_to_steering_status: false
diff --git a/autoware_launch/launch/components/tier4_localization_component.launch.xml b/autoware_launch/launch/components/tier4_localization_component.launch.xml
index 7dfe0a3dea..f7a2db6922 100644
--- a/autoware_launch/launch/components/tier4_localization_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_localization_component.launch.xml
@@ -19,6 +19,7 @@
+
@@ -51,6 +52,14 @@
+
+
+
+
+
diff --git a/autoware_launch/launch/e2e_simulator.launch.xml b/autoware_launch/launch/e2e_simulator.launch.xml
index 1372d04e7c..347e3c977c 100644
--- a/autoware_launch/launch/e2e_simulator.launch.xml
+++ b/autoware_launch/launch/e2e_simulator.launch.xml
@@ -37,6 +37,8 @@
default="$(find-pkg-share autoware_launch)/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml"
description="system error monitor param path"
/>
+
+
@@ -74,7 +76,7 @@
-
+
diff --git a/autoware_launch/rviz/scenario_simulator.rviz b/autoware_launch/rviz/scenario_simulator.rviz
new file mode 100644
index 0000000000..d0b57f225b
--- /dev/null
+++ b/autoware_launch/rviz/scenario_simulator.rviz
@@ -0,0 +1,3151 @@
+Panels:
+ - Class: rviz_common/Displays
+ Help Height: 0
+ Name: Displays
+ Property Tree Widget:
+ Expanded:
+ - /Sensing1/LiDAR1/ConcatenatePointCloud1/Autocompute Value Bounds1
+ Splitter Ratio: 0.557669460773468
+ Tree Height: 1060
+ - Class: rviz_common/Tool Properties
+ Expanded: ~
+ Name: Tool Properties
+ Splitter Ratio: 0.5886790156364441
+ - Class: rviz_common/Views
+ Expanded:
+ - /Current View1
+ Name: Views
+ Splitter Ratio: 0.5
+ - Class: rviz_plugins::AutowareStatePanel
+ Name: AutowareStatePanel
+Visualization Manager:
+ Class: ""
+ Displays:
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/TF
+ Enabled: false
+ Frame Timeout: 15
+ Frames:
+ All Enabled: true
+ Marker Scale: 1
+ Name: TF
+ Show Arrows: true
+ Show Axes: true
+ Show Names: true
+ Tree: {}
+ Update Interval: 0
+ Value: false
+ - Alpha: 0.5
+ Cell Size: 1
+ Class: rviz_default_plugins/Grid
+ Color: 160; 160; 164
+ Enabled: false
+ Line Style:
+ Line Width: 0.029999999329447746
+ Value: Lines
+ Name: Grid
+ Normal Cell Count: 0
+ Offset:
+ X: 0
+ Y: 0
+ Z: 0
+ Plane: XY
+ Plane Cell Count: 10
+ Reference Frame:
+ Value: false
+ - Class: rviz_common/Group
+ Displays:
+ - Alpha: 0.30000001192092896
+ Class: rviz_default_plugins/RobotModel
+ Collision Enabled: false
+ Description File: ""
+ Description Source: Topic
+ Description Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /robot_description
+ Enabled: true
+ Links:
+ All Links Enabled: true
+ Expand Joint Details: false
+ Expand Link Details: false
+ Expand Tree: false
+ Link Tree Style: Links in Alphabetic Order
+ base_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ camera0/camera_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ camera0/camera_optical_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ camera1/camera_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ camera1/camera_optical_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ camera2/camera_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ camera2/camera_optical_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ camera3/camera_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ camera3/camera_optical_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ camera4/camera_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ camera4/camera_optical_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ camera5/camera_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ camera5/camera_optical_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ gnss_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ sensor_kit_base_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ tamagawa/imu_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ traffic_light_left_camera/camera_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ traffic_light_left_camera/camera_optical_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ traffic_light_right_camera/camera_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ traffic_light_right_camera/camera_optical_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ velodyne_left:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ velodyne_left_base_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ velodyne_rear:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ velodyne_rear_base_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ velodyne_right:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ velodyne_right_base_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ velodyne_top:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ velodyne_top_base_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ Mass Properties:
+ Inertia: false
+ Mass: false
+ Name: VehicleModel
+ TF Prefix: ""
+ Update Interval: 0
+ Value: true
+ Visual Enabled: true
+ - Class: rviz_plugins/PolarGridDisplay
+ Color: 255; 255; 255
+ Delta Range: 10
+ Enabled: true
+ Max Alpha: 0.5
+ Max Range: 100
+ Max Wave Alpha: 0.5
+ Min Alpha: 0.009999999776482582
+ Min Wave Alpha: 0.009999999776482582
+ Name: PolarGridDisplay
+ Reference Frame: base_link
+ Value: true
+ Wave Color: 255; 255; 255
+ Wave Velocity: 40
+ - Background Alpha: 0.30000001192092896
+ Background Color: 0; 0; 0
+ Class: autoware_overlay_rviz_plugin/SignalDisplay
+ Dark Traffic Color: 255; 51; 51
+ Enabled: true
+ Gear Topic Test: /vehicle/status/gear_status
+ Handle Angle Scale: 17
+ Hazard Lights Topic: /vehicle/status/hazard_lights_status
+ Height: 100
+ Left: 0
+ Light Traffic Color: 255; 153; 153
+ Name: SignalDisplay
+ Primary Color: 174; 174; 174
+ Signal Color: 0; 230; 120
+ Speed Limit Topic: /planning/scenario_planning/current_max_velocity
+ Speed Topic: /vehicle/status/velocity_status
+ Steering Topic: /vehicle/status/steering_status
+ Top: 10
+ Traffic Topic: /planning/scenario_planning/lane_driving/behavior_planning/debug/traffic_signal
+ Turn Signals Topic: /vehicle/status/turn_indicators_status
+ Value: true
+ Width: 550
+ Enabled: true
+ Name: Vehicle
+ Enabled: true
+ Name: System
+ - Class: rviz_common/Group
+ Displays:
+ - Alpha: 0.20000000298023224
+ Autocompute Intensity Bounds: true
+ Autocompute Value Bounds:
+ Max Value: 28.71826171875
+ Min Value: -7.4224700927734375
+ Value: true
+ Axis: Z
+ Channel Name: intensity
+ Class: rviz_default_plugins/PointCloud2
+ Color: 255; 255; 255
+ Color Transformer: FlatColor
+ Decay Time: 0
+ Enabled: false
+ Invert Rainbow: false
+ Max Color: 255; 255; 255
+ Max Intensity: 237
+ Min Color: 211; 215; 207
+ Min Intensity: 0
+ Name: PointCloudMap
+ Position Transformer: XYZ
+ Selectable: false
+ Size (Pixels): 1
+ Size (m): 0.019999999552965164
+ Style: Points
+ Topic:
+ Depth: 5
+ Durability Policy: Transient Local
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /map/pointcloud_map
+ Use Fixed Frame: true
+ Use rainbow: false
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Lanelet2VectorMap
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Transient Local
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /map/vector_map_marker
+ Value: false
+ Enabled: true
+ Name: Map
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_common/Group
+ Displays:
+ - Alpha: 0.4000000059604645
+ Autocompute Intensity Bounds: true
+ Autocompute Value Bounds:
+ Max Value: 5
+ Min Value: -1
+ Value: false
+ Axis: Z
+ Channel Name: intensity
+ Class: rviz_default_plugins/PointCloud2
+ Color: 255; 255; 255
+ Color Transformer: AxisColor
+ Decay Time: 0
+ Enabled: true
+ Invert Rainbow: false
+ Max Color: 255; 255; 255
+ Max Intensity: 4096
+ Min Color: 0; 0; 0
+ Min Intensity: 0
+ Name: ConcatenatePointCloud
+ Position Transformer: XYZ
+ Selectable: false
+ Size (Pixels): 1
+ Size (m): 0.019999999552965164
+ Style: Points
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /sensing/lidar/concatenated/pointcloud
+ Use Fixed Frame: false
+ Use rainbow: true
+ Value: true
+ - Alpha: 0.9990000128746033
+ Class: rviz_default_plugins/Polygon
+ Color: 25; 255; 0
+ Enabled: false
+ Name: MeasurementRange
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /sensing/lidar/crop_box_filter/crop_box_polygon
+ Value: false
+ Enabled: true
+ Name: LiDAR
+ - Class: rviz_common/Group
+ Displays:
+ - Alpha: 0.9990000128746033
+ Axes Length: 1
+ Axes Radius: 0.10000000149011612
+ Class: rviz_default_plugins/PoseWithCovariance
+ Color: 233; 185; 110
+ Covariance:
+ Orientation:
+ Alpha: 0.5
+ Color: 255; 255; 127
+ Color Style: Unique
+ Frame: Local
+ Offset: 1
+ Scale: 1
+ Value: false
+ Position:
+ Alpha: 0.20000000298023224
+ Color: 204; 51; 204
+ Scale: 1
+ Value: true
+ Value: true
+ Enabled: true
+ Head Length: 0.699999988079071
+ Head Radius: 1.2000000476837158
+ Name: PoseWithCovariance
+ Shaft Length: 1
+ Shaft Radius: 0.5
+ Shape: Arrow
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /sensing/gnss/pose_with_covariance
+ Value: true
+ Enabled: false
+ Name: GNSS
+ Enabled: true
+ Name: Sensing
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_common/Group
+ Displays:
+ - Alpha: 0.9990000128746033
+ Axes Length: 1
+ Axes Radius: 0.10000000149011612
+ Class: rviz_default_plugins/PoseWithCovariance
+ Color: 0; 170; 255
+ Covariance:
+ Orientation:
+ Alpha: 0.5
+ Color: 255; 255; 127
+ Color Style: Unique
+ Frame: Local
+ Offset: 1
+ Scale: 1
+ Value: true
+ Position:
+ Alpha: 0.30000001192092896
+ Color: 204; 51; 204
+ Scale: 1
+ Value: true
+ Value: true
+ Enabled: false
+ Head Length: 0.4000000059604645
+ Head Radius: 0.6000000238418579
+ Name: PoseWithCovInitial
+ Shaft Length: 0.6000000238418579
+ Shaft Radius: 0.30000001192092896
+ Shape: Arrow
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /localization/pose_estimator/initial_pose_with_covariance
+ Value: false
+ - Alpha: 0.9990000128746033
+ Axes Length: 1
+ Axes Radius: 0.10000000149011612
+ Class: rviz_default_plugins/PoseWithCovariance
+ Color: 0; 255; 0
+ Covariance:
+ Orientation:
+ Alpha: 0.5
+ Color: 255; 255; 127
+ Color Style: Unique
+ Frame: Local
+ Offset: 1
+ Scale: 1
+ Value: true
+ Position:
+ Alpha: 0.30000001192092896
+ Color: 204; 51; 204
+ Scale: 1
+ Value: true
+ Value: true
+ Enabled: false
+ Head Length: 0.4000000059604645
+ Head Radius: 0.6000000238418579
+ Name: PoseWithCovAligned
+ Shaft Length: 0.6000000238418579
+ Shaft Radius: 0.30000001192092896
+ Shape: Arrow
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /localization/pose_estimator/pose_with_covariance
+ Value: false
+ - Buffer Size: 200
+ Class: rviz_plugins::PoseHistory
+ Enabled: false
+ Line:
+ Alpha: 0.9990000128746033
+ Color: 170; 255; 127
+ Value: true
+ Width: 0.10000000149011612
+ Name: PoseHistory
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /localization/pose_estimator/pose
+ Value: false
+ - Alpha: 0.9990000128746033
+ Autocompute Intensity Bounds: true
+ Autocompute Value Bounds:
+ Max Value: 10
+ Min Value: -10
+ Value: true
+ Axis: Z
+ Channel Name: intensity
+ Class: rviz_default_plugins/PointCloud2
+ Color: 0; 255; 255
+ Color Transformer: ""
+ Decay Time: 0
+ Enabled: false
+ Invert Rainbow: false
+ Max Color: 255; 255; 255
+ Max Intensity: 4096
+ Min Color: 0; 0; 0
+ Min Intensity: 0
+ Name: Initial
+ Position Transformer: XYZ
+ Selectable: false
+ Size (Pixels): 10
+ Size (m): 0.5
+ Style: Squares
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /localization/util/downsample/pointcloud
+ Use Fixed Frame: true
+ Use rainbow: true
+ Value: false
+ - Alpha: 0.9990000128746033
+ Autocompute Intensity Bounds: true
+ Autocompute Value Bounds:
+ Max Value: 10
+ Min Value: -10
+ Value: true
+ Axis: Z
+ Channel Name: intensity
+ Class: rviz_default_plugins/PointCloud2
+ Color: 85; 255; 0
+ Color Transformer: FlatColor
+ Decay Time: 0
+ Enabled: false
+ Invert Rainbow: false
+ Max Color: 85; 255; 127
+ Max Intensity: 0
+ Min Color: 0; 0; 0
+ Min Intensity: 0
+ Name: Aligned
+ Position Transformer: XYZ
+ Selectable: false
+ Size (Pixels): 10
+ Size (m): 0.5
+ Style: Squares
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /localization/pose_estimator/points_aligned
+ Use Fixed Frame: true
+ Use rainbow: true
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: MonteCarloInitialPose
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /localization/pose_estimator/monte_carlo_initial_pose_marker
+ Value: true
+ Enabled: true
+ Name: NDT
+ - Class: rviz_common/Group
+ Displays:
+ - Buffer Size: 1000
+ Class: rviz_plugins::PoseHistory
+ Enabled: true
+ Line:
+ Alpha: 0.9990000128746033
+ Color: 0; 255; 255
+ Value: true
+ Width: 0.10000000149011612
+ Name: PoseHistory
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /localization/pose_twist_fusion_filter/pose
+ Value: true
+ Enabled: true
+ Name: EKF
+ Enabled: true
+ Name: Localization
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_common/Group
+ Displays:
+ - Alpha: 0.9990000128746033
+ Autocompute Intensity Bounds: true
+ Autocompute Value Bounds:
+ Max Value: 15
+ Min Value: -2
+ Value: false
+ Axis: Z
+ Channel Name: z
+ Class: rviz_default_plugins/PointCloud2
+ Color: 200; 200; 200
+ Color Transformer: FlatColor
+ Decay Time: 0
+ Enabled: true
+ Invert Rainbow: false
+ Max Color: 255; 255; 255
+ Max Intensity: 15
+ Min Color: 0; 0; 0
+ Min Intensity: -5
+ Name: NoGroundPointCloud
+ Position Transformer: XYZ
+ Selectable: false
+ Size (Pixels): 3
+ Size (m): 0.019999999552965164
+ Style: Points
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /perception/obstacle_segmentation/pointcloud
+ Use Fixed Frame: true
+ Use rainbow: true
+ Value: true
+ Enabled: true
+ Name: Segmentation
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_common/Group
+ Displays:
+ - BUS:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CAR:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CYCLIST:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Class: autoware_perception_rviz_plugin/DetectedObjects
+ Display Acceleration: true
+ Display Label: true
+ Display PoseWithCovariance: true
+ Display Predicted Path Confidence: true
+ Display Predicted Paths: true
+ Display Twist: true
+ Display UUID: true
+ Display Velocity: true
+ Enabled: true
+ Line Width: 0.029999999329447746
+ MOTORCYCLE:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Name: DetectedObjects
+ Namespaces: ~
+ PEDESTRIAN:
+ Alpha: 0.9990000128746033
+ Color: 255; 192; 203
+ Polygon Type: 3d
+ TRAILER:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ TRUCK:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /perception/object_recognition/detection/objects
+ UNKNOWN:
+ Alpha: 0.9990000128746033
+ Color: 255; 255; 255
+ Value: true
+ Visualization Type: Normal
+ Enabled: false
+ Name: Detection
+ - Class: rviz_common/Group
+ Displays:
+ - BUS:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CAR:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CYCLIST:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Class: autoware_perception_rviz_plugin/TrackedObjects
+ Display Acceleration: true
+ Display Label: true
+ Display PoseWithCovariance: true
+ Display Predicted Path Confidence: true
+ Display Predicted Paths: true
+ Display Twist: true
+ Display UUID: true
+ Display Velocity: true
+ Enabled: true
+ Line Width: 0.029999999329447746
+ MOTORCYCLE:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Name: TrackedObjects
+ Namespaces: ~
+ PEDESTRIAN:
+ Alpha: 0.9990000128746033
+ Color: 255; 192; 203
+ Polygon Type: 3d
+ TRAILER:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ TRUCK:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /perception/object_recognition/tracking/objects
+ UNKNOWN:
+ Alpha: 0.9990000128746033
+ Color: 255; 255; 255
+ Value: true
+ Visualization Type: Normal
+ Enabled: false
+ Name: Tracking
+ - Class: rviz_common/Group
+ Displays:
+ - BUS:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CAR:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CYCLIST:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Class: autoware_perception_rviz_plugin/PredictedObjects
+ Display Acceleration: true
+ Display Label: true
+ Display PoseWithCovariance: false
+ Display Predicted Path Confidence: true
+ Display Predicted Paths: true
+ Display Twist: true
+ Display UUID: true
+ Display Velocity: true
+ Enabled: true
+ Line Width: 0.5
+ MOTORCYCLE:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Name: PredictedObjects
+ Namespaces: ~
+ PEDESTRIAN:
+ Alpha: 0.9990000128746033
+ Color: 255; 192; 203
+ Polygon Type: 3d
+ TRAILER:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ TRUCK:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /perception/object_recognition/objects
+ UNKNOWN:
+ Alpha: 0.9990000128746033
+ Color: 255; 255; 255
+ Value: true
+ Visualization Type: Normal
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Maneuver
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /perception/object_recognition/prediction/maneuver
+ Value: false
+ Enabled: true
+ Name: Prediction
+ Enabled: true
+ Name: ObjectRecognition
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/Image
+ Enabled: false
+ Max Value: 1
+ Median window: 5
+ Min Value: 0
+ Name: RecognitionResultOnImage
+ Normalize Range: true
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /perception/traffic_light_recognition/debug/rois
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: MapBasedDetectionResult
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers
+ Value: true
+ Enabled: true
+ Name: TrafficLight
+ - Class: rviz_common/Group
+ Displays:
+ - Alpha: 0.5
+ Class: rviz_default_plugins/Map
+ Color Scheme: map
+ Draw Behind: false
+ Enabled: true
+ Name: Map
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /perception/occupancy_grid_map/map
+ Update Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /perception/occupancy_grid_map/map_updates
+ Use Timestamp: false
+ Value: true
+ Enabled: false
+ Name: OccupancyGrid
+ Enabled: true
+ Name: Perception
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: RouteArea
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Transient Local
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/mission_planning/route_marker
+ Value: true
+ - Alpha: 0.9990000128746033
+ Axes Length: 1
+ Axes Radius: 0.30000001192092896
+ Class: rviz_default_plugins/Pose
+ Color: 255; 25; 0
+ Enabled: true
+ Head Length: 0.30000001192092896
+ Head Radius: 0.5
+ Name: GoalPose
+ Shaft Length: 3
+ Shaft Radius: 0.20000000298023224
+ Shape: Axes
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/mission_planning/echo_back_goal_pose
+ Value: true
+ - Background Alpha: 0.30000001192092896
+ Background Color: 0; 0; 0
+ Class: autoware_mission_details_overlay_rviz_plugin/MissionDetailsDisplay
+ Enabled: true
+ Height: 100
+ Name: MissionDetailsDisplay
+ Remaining Distance and Time Topic: /planning/mission_remaining_distance_time
+ Right: 10
+ Text Color: 194; 194; 194
+ Top: 10
+ Value: true
+ Width: 170
+ Enabled: true
+ Name: MissionPlanning
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_plugins/Trajectory
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: ScenarioTrajectory
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/trajectory
+ Value: true
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.9990000128746033
+ Color: 0; 0; 0
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.9990000128746033
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: true
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: Path
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/path
+ Value: true
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.4000000059604645
+ Color: 0; 0; 0
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.4000000059604645
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: true
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: false
+ Name: PathReference_AvoidanceByLC
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_reference/avoidance_by_lane_change
+ Value: false
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 210; 110; 10
+ Constant Color: true
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: false
+ Name: PathReference_Avoidance
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_reference/avoidance
+ Value: false
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 210; 110; 210
+ Constant Color: true
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: false
+ Name: PathReference_LaneChangeRight
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_reference/lane_change_right
+ Value: false
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 210; 210; 110
+ Constant Color: true
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: false
+ Name: PathReference_LaneChangeLeft
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_reference/lane_change_left
+ Value: false
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 210; 210; 110
+ Constant Color: true
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: false
+ Name: PathReference_GoalPlanner
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_reference/goal_planner
+ Value: false
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 110; 110; 210
+ Constant Color: true
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: false
+ Name: PathReference_StartPlanner
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_reference/start_planner
+ Value: false
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 210; 110; 110
+ Constant Color: true
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: PathChangeCandidate_AvoidanceByLC
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_candidate/avoidance_by_lane_change
+ Value: true
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 115; 210; 22
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: (old)PathChangeCandidate_LaneChange
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_candidate/lane_change
+ Value: true
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 115; 210; 22
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: PathChangeCandidate_LaneChangeRight
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_candidate/lane_change_right
+ Value: true
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 115; 210; 22
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: PathChangeCandidate_LaneChangeLeft
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_candidate/lane_change_left
+ Value: true
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 115; 210; 22
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: PathChangeCandidate_ExternalRequestLaneChangeRight
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_candidate/external_request_lane_change_right
+ Value: true
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 115; 210; 22
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: PathChangeCandidate_ExternalRequestLaneChangeLeft
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_candidate/external_request_lane_change_left
+ Value: true
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 115; 210; 22
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: PathChangeCandidate_Avoidance
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_candidate/avoidance
+ Value: true
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 115; 210; 22
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: PathChangeCandidate_StartPlanner
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_candidate/start_planner
+ Value: true
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 115; 210; 22
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_plugins/Path
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: PathChangeCandidate_GoalPlanner
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/path_candidate/goal_planner
+ Value: true
+ View Drivable Area:
+ Alpha: 0.9990000128746033
+ Color: 0; 148; 205
+ Value: true
+ Width: 0.30000001192092896
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.30000001192092896
+ Color: 115; 210; 22
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.30000001192092896
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Bound
+ Namespaces: {}
+ 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/bound
+ Value: false
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (Avoidance)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ 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: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (AvoidanceByLC)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/avoidance_by_lane_change
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (LaneChangeRight)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/lane_change_right
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (LaneChangeLeft)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/lane_change_left
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (ExtLaneChangeRight)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/external_request_lane_change_right
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (ExtLaneChangeLeft)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/external_request_lane_change_left
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (GoalPlanner)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/goal_planner
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (StartPlanner)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/start_planner
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (BlindSpot)
+ 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/blind_spot
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (Crosswalk)
+ 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/crosswalk
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (Walkway)
+ 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/walkway
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (DetectionArea)
+ 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/detection_area
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (Intersection)
+ 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/intersection
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (MergeFromPrivateArea)
+ 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/merge_from_private
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (NoStoppingArea)
+ 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/no_stopping_area
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (OcclusionSpot)
+ 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/occlusion_spot
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (StopLine)
+ 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/stop_line
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (TrafficLight)
+ 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/traffic_light
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (VirtualTrafficLight)
+ 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/virtual_traffic_light
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (RunOut)
+ 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/run_out
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (SpeedBump)
+ 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/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)
+ 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/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
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Arrow
+ 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/path
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Crosswalk
+ 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/crosswalk
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Intersection
+ 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/intersection
+ Value: false
+ - Alpha: 0.5
+ Autocompute Intensity Bounds: true
+ Class: grid_map_rviz_plugin/GridMap
+ Color: 200; 200; 200
+ Color Layer: color
+ Color Transformer: IntensityLayer
+ Enabled: false
+ Height Layer: elevation
+ Height Transformer: Layer
+ History Length: 1
+ Invert Rainbow: false
+ Max Color: 255; 255; 255
+ Max Intensity: 10
+ Min Color: 0; 0; 0
+ Min Intensity: 0
+ Name: IntersectionOcclusion
+ Show Grid Lines: false
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection/occlusion_grid
+ Use Rainbow: true
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Blind Spot
+ 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/blind_spot
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: TrafficLight
+ 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/traffic_light
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: VirtualTrafficLight
+ 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/virtual_traffic_light
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: StopLine
+ 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/stop_line
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: DetectionArea
+ 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/detection_area
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: OcclusionSpot
+ 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/occlusion_spot
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: NoStoppingArea
+ 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/no_stopping_area
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: RunOut
+ 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/run_out
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Avoidance
+ Namespaces: {}
+ 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/avoidance
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: LaneChange
+ Namespaces: {}
+ 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/lane_change
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: LaneFollowing
+ Namespaces: {}
+ 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/lane_following
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: GoalPlanner
+ Namespaces: {}
+ 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/goal_planner
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: StartPlanner
+ Namespaces: {}
+ 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/start_planner
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: SideShift
+ Namespaces: {}
+ 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/side_shift
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: SpeedBump
+ 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/speed_bump
+ 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
+ Namespaces: {}
+ 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/dynamic_avoidance
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: NoDrivableLane
+ 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/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)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/avoidance
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Info (AvoidanceByLC)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/avoidance_by_lane_change
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Info (LaneChangeLeft)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/lane_change_left
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Info (LaneChangeRight)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/lane_change_right
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Info (ExtLaneChangeLeft)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/external_request_lane_change_left
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Info (ExtLaneChangeRight)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/external_request_lane_change_right
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Info (GoalPlanner)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/goal_planner
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Info (StartPlanner)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/start_planner
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Info (DynamicAvoidance)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ 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: false
+ Enabled: false
+ Name: InfoMarker
+ Enabled: true
+ Name: BehaviorPlanning
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_plugins/Trajectory
+ Color Border Vel Max: 3
+ Enabled: false
+ Name: Trajectory
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/trajectory
+ Value: false
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 0.9990000128746033
+ Color: 0; 0; 0
+ Constant Color: false
+ Constant Width: false
+ Value: true
+ Width: 2
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 0.9990000128746033
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: true
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (ObstacleStop)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/virtual_wall
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (SurroundObstacle)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/virtual_wall
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (ObstacleAvoidance)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/virtual_wall
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (ObstacleCruise)
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/virtual_wall
+ Value: true
+ Enabled: true
+ Name: VirtualWall
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: SurroundObstacleCheck
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker
+ Value: true
+ - Alpha: 1
+ Class: rviz_default_plugins/Polygon
+ Color: 25; 255; 0
+ Enabled: false
+ Name: Footprint
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint
+ Value: false
+ - Alpha: 1
+ Class: rviz_default_plugins/Polygon
+ Color: 239; 41; 41
+ Enabled: false
+ Name: FootprintOffset
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint_offset
+ Value: false
+ - Alpha: 1
+ Class: rviz_default_plugins/Polygon
+ Color: 10; 21; 255
+ Enabled: false
+ Name: FootprintRecoverOffset
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint_recover_offset
+ Value: false
+ Enabled: false
+ Name: SurroundObstacleChecker
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: ObstacleStop
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker
+ Value: false
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: CruiseVirtualWall
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/cruise/virtual_wall
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: SlowDownVirtualWall
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/slow_down/virtual_wall
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: DebugMarker
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/marker
+ Value: true
+ Enabled: false
+ Name: ObstacleCruise
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: ObstacleAvoidance
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker
+ Value: false
+ Enabled: false
+ Name: DebugMarker
+ Enabled: true
+ Name: MotionPlanning
+ Enabled: true
+ Name: LaneDriving
+ - Class: rviz_common/Group
+ Displays:
+ - Alpha: 0.699999988079071
+ Class: rviz_default_plugins/Map
+ Color Scheme: map
+ Draw Behind: false
+ Enabled: false
+ Name: Costmap
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/parking/costmap_generator/occupancy_grid
+ Update Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/parking/costmap_generator/occupancy_grid_updates
+ Use Timestamp: false
+ Value: false
+ - Alpha: 0.9990000128746033
+ Arrow Length: 0.30000001192092896
+ Axes Length: 0.30000001192092896
+ Axes Radius: 0.009999999776482582
+ Class: rviz_default_plugins/PoseArray
+ Color: 255; 25; 0
+ Enabled: true
+ Head Length: 0.10000000149011612
+ Head Radius: 0.20000000298023224
+ Name: PartialPoseArray
+ Shaft Length: 0.20000000298023224
+ Shaft Radius: 0.05000000074505806
+ Shape: Arrow (3D)
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/parking/freespace_planner/debug/partial_pose_array
+ Value: true
+ - Alpha: 0.9990000128746033
+ Arrow Length: 0.5
+ Axes Length: 0.30000001192092896
+ Axes Radius: 0.009999999776482582
+ Class: rviz_default_plugins/PoseArray
+ Color: 0; 0; 255
+ Enabled: true
+ Head Length: 0.10000000149011612
+ Head Radius: 0.20000000298023224
+ Name: PoseArray
+ Shaft Length: 0.20000000298023224
+ Shaft Radius: 0.05000000074505806
+ Shape: Arrow (Flat)
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/parking/freespace_planner/debug/pose_array
+ Value: true
+ Enabled: true
+ Name: Parking
+ - Class: rviz_plugins/PoseWithUuidStamped
+ Enabled: true
+ Length: 1.5
+ Name: ModifiedGoal
+ Radius: 0.5
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/modified_goal
+ UUID:
+ Scale: 0.30000001192092896
+ Value: false
+ Value: true
+ Enabled: true
+ Name: ScenarioPlanning
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: PlanningErrorMarker
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /planning/planning_diagnostics/planning_error_monitor/debug/marker
+ Value: true
+ Enabled: false
+ Name: Diagnostic
+ Enabled: true
+ Name: Planning
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_plugins/Trajectory
+ Color Border Vel Max: 3
+ Enabled: true
+ Name: Predicted Trajectory
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /control/trajectory_follower/lateral/predicted_trajectory
+ Value: true
+ View Footprint:
+ Alpha: 1
+ Color: 230; 230; 50
+ Offset from BaseLink: 0
+ Rear Overhang: 1.0299999713897705
+ Value: false
+ Vehicle Length: 4.769999980926514
+ Vehicle Width: 1.8300000429153442
+ View Path:
+ Alpha: 1
+ Color: 255; 255; 255
+ Constant Color: true
+ Constant Width: true
+ Value: true
+ Width: 0.05000000074505806
+ View Point:
+ Alpha: 1
+ Color: 0; 60; 255
+ Offset: 0
+ Radius: 0.10000000149011612
+ Value: false
+ View Text Slope:
+ Scale: 0.30000001192092896
+ Value: false
+ View Text Velocity:
+ Scale: 0.30000001192092896
+ Value: false
+ View Velocity:
+ Alpha: 1
+ Color: 0; 0; 0
+ Constant Color: false
+ Scale: 0.30000001192092896
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Debug/MPC
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /control/trajectory_follower/mpc_follower/debug/markers
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Debug/PurePursuit
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /control/trajectory_follower/controller_node_exe/debug/markers
+ Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: Debug/AEB
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /control/autonomous_emergency_braking/debug/markers
+ Value: false
+ Enabled: true
+ Name: Control
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: Debug Marker
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /simulation/debug_marker
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: Entity Marker
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /simulation/entity/marker
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: Lanelet Marker
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Transient Local
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /simulation/lanelet/marker
+ Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: Traffic Light Marker
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /simulation/traffic_light/marker
+ Value: true
+ - Class: openscenario_visualization/VisualizationConditionGroups
+ Enabled: true
+ Left: 0
+ Length: 2000
+ Name: Condition Group
+ Text Color: 255; 255; 255
+ Top: 450
+ Topic: /simulation/context
+ Value: true
+ Value Scale: 35
+ Width: 2000
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: Debug Marker
+ Namespaces: {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /simulation/debug_marker
+ Value: true
+ - Class: rviz_common/Group
+ Displays:
+ - Alpha: 0.9990000128746033
+ Autocompute Intensity Bounds: true
+ Autocompute Value Bounds:
+ Max Value: 10
+ Min Value: -10
+ Value: true
+ Axis: Z
+ Channel Name: intensity
+ Class: rviz_default_plugins/PointCloud2
+ Color: 255; 255; 255
+ Color Transformer: FlatColor
+ Decay Time: 0
+ Enabled: true
+ Invert Rainbow: false
+ Max Color: 255; 255; 255
+ Max Intensity: 0
+ Min Color: 0; 0; 0
+ Min Intensity: 0
+ Name: Simple LiDAR
+ Position Transformer: XYZ
+ Selectable: true
+ Size (Pixels): 3
+ Size (m): 3
+ Style: Points
+ Topic:
+ Depth: 5
+ Durability Policy: System Default
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /perception/obstacle_segmentation/pointcloud
+ Use Fixed Frame: true
+ Use rainbow: true
+ Value: true
+ - BUS:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CAR:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CYCLIST:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Class: autoware_perception_rviz_plugin/DetectedObjects
+ Display Acceleration: true
+ Display Label: true
+ Display PoseWithCovariance: true
+ Display Predicted Path Confidence: true
+ Display Predicted Paths: true
+ Display Twist: true
+ Display UUID: true
+ Display Velocity: true
+ Enabled: true
+ Line Width: 0.029999999329447746
+ MOTORCYCLE:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Name: Detected Objects
+ Namespaces: ~
+ PEDESTRIAN:
+ Alpha: 0.9990000128746033
+ Color: 255; 192; 203
+ Polygon Type: 3d
+ TRAILER:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ TRUCK:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /perception/object_recognition/detection/objects
+ UNKNOWN:
+ Alpha: 0.9990000128746033
+ Color: 255; 255; 255
+ Value: true
+ Visualization Type: Normal
+ - Alpha: 0.699999988079071
+ Class: rviz_default_plugins/Map
+ Color Scheme: map
+ Draw Behind: false
+ Enabled: false
+ Name: Occupancy Grid Map
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /perception/occupancy_grid_map/map
+ Update Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /perception/occupancy_grid_map/map_updates
+ Use Timestamp: false
+ Value: false
+ Enabled: true
+ Name: Simple Sensor Simulator
+ Enabled: true
+ Name: Simulation
+ Enabled: true
+ Global Options:
+ Background Color: 10; 10; 10
+ Fixed Frame: map
+ Frame Rate: 30
+ Name: root
+ Tools:
+ - Class: rviz_default_plugins/Interact
+ Hide Inactive Objects: true
+ - Class: rviz_default_plugins/MoveCamera
+ - Class: rviz_default_plugins/Select
+ - Class: rviz_default_plugins/FocusCamera
+ - Class: rviz_default_plugins/Measure
+ Line color: 128; 128; 0
+ - Class: rviz_default_plugins/SetInitialPose
+ Covariance x: 0.25
+ Covariance y: 0.25
+ Covariance yaw: 0.06853891909122467
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /initialpose
+ - Class: rviz_default_plugins/SetGoal
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/mission_planning/goal
+ - Class: tier4_adapi_rviz_plugins::RouteTool
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /rviz/routing/rough_goal
+ - Acceleration: 0
+ Class: rviz_plugins/PedestrianInitialPoseTool
+ Interactive: false
+ Max velocity: 33.29999923706055
+ Min velocity: -33.29999923706055
+ Pose Topic: /simulation/dummy_perception_publisher/object_info
+ Target Frame:
+ Theta std deviation: 0.0872664600610733
+ Velocity: 0
+ X std deviation: 0.029999999329447746
+ Y std deviation: 0.029999999329447746
+ Z position: 1
+ Z std deviation: 0.029999999329447746
+ - Acceleration: 0
+ Class: rviz_plugins/CarInitialPoseTool
+ H vehicle height: 2
+ Interactive: false
+ L vehicle length: 4
+ Max velocity: 33.29999923706055
+ Min velocity: -33.29999923706055
+ Pose Topic: /simulation/dummy_perception_publisher/object_info
+ Target Frame:
+ Theta std deviation: 0.0872664600610733
+ Velocity: 3
+ W vehicle width: 1.7999999523162842
+ X std deviation: 0.029999999329447746
+ Y std deviation: 0.029999999329447746
+ Z position: 0
+ Z std deviation: 0.029999999329447746
+ - Acceleration: 0
+ Class: rviz_plugins/BusInitialPoseTool
+ H vehicle height: 3.5
+ Interactive: false
+ L vehicle length: 10.5
+ Max velocity: 33.29999923706055
+ Min velocity: -33.29999923706055
+ Pose Topic: /simulation/dummy_perception_publisher/object_info
+ Target Frame:
+ Theta std deviation: 0.0872664600610733
+ Velocity: 0
+ W vehicle width: 2.5
+ X std deviation: 0.029999999329447746
+ Y std deviation: 0.029999999329447746
+ Z position: 0
+ Z std deviation: 0.029999999329447746
+ - Class: rviz_plugins/MissionCheckpointTool
+ Pose Topic: /planning/mission_planning/checkpoint
+ Theta std deviation: 0.2617993950843811
+ X std deviation: 0.5
+ Y std deviation: 0.5
+ Z position: 0
+ - Class: rviz_plugins/DeleteAllObjectsTool
+ Pose Topic: /simulation/dummy_perception_publisher/object_info
+ Transformation:
+ Current:
+ Class: rviz_default_plugins/TF
+ Value: true
+ Views:
+ Current:
+ Angle: 0
+ Class: rviz_default_plugins/TopDownOrtho
+ Enable Stereo Rendering:
+ Stereo Eye Separation: 0.05999999865889549
+ Stereo Focal Distance: 1
+ Swap Stereo Eyes: false
+ Value: false
+ Invert Z Axis: false
+ Name: Current View
+ Near Clip Distance: 0.009999999776482582
+ Scale: 10
+ Target Frame: entities
+ Value: TopDownOrtho (rviz_default_plugins)
+ X: 0
+ Y: 0
+ Saved:
+ - Class: rviz_default_plugins/ThirdPersonFollower
+ Distance: 18
+ Enable Stereo Rendering:
+ Stereo Eye Separation: 0.05999999865889549
+ Stereo Focal Distance: 1
+ Swap Stereo Eyes: false
+ Value: false
+ Focal Point:
+ X: 0
+ Y: 0
+ Z: 0
+ Focal Shape Fixed Size: true
+ Focal Shape Size: 0.05000000074505806
+ Invert Z Axis: false
+ Name: ThirdPersonFollower
+ Near Clip Distance: 0.009999999776482582
+ Pitch: 0.20000000298023224
+ Target Frame: base_link
+ Value: ThirdPersonFollower (rviz)
+ Yaw: 3.141592025756836
+ - Angle: 0
+ Class: rviz_default_plugins/TopDownOrtho
+ Enable Stereo Rendering:
+ Stereo Eye Separation: 0.05999999865889549
+ Stereo Focal Distance: 1
+ Swap Stereo Eyes: false
+ Value: false
+ Invert Z Axis: false
+ Name: TopDownOrtho
+ Near Clip Distance: 0.009999999776482582
+ Scale: 10
+ Target Frame: viewer
+ Value: TopDownOrtho (rviz)
+ X: 0
+ Y: 0
+Window Geometry:
+ AutowareStatePanel:
+ collapsed: false
+ Displays:
+ collapsed: false
+ Height: 2091
+ Hide Left Dock: false
+ Hide Right Dock: false
+ QMainWindow State: 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
+ RecognitionResultOnImage:
+ collapsed: false
+ Tool Properties:
+ collapsed: false
+ Views:
+ collapsed: false
+ Width: 3770
+ X: 1920
+ Y: 0