diff --git a/launch/autoware_launch/CMakeLists.txt b/launch/autoware_launch/CMakeLists.txt new file mode 100644 index 0000000000000..60e4e952cb320 --- /dev/null +++ b/launch/autoware_launch/CMakeLists.txt @@ -0,0 +1,16 @@ +cmake_minimum_required(VERSION 3.5) +project(autoware_launch) + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package( + INSTALL_TO_SHARE + launch + rviz +) diff --git a/launch/autoware_launch/README.md b/launch/autoware_launch/README.md new file mode 100644 index 0000000000000..61f7f4a3b7867 --- /dev/null +++ b/launch/autoware_launch/README.md @@ -0,0 +1,17 @@ +# autoware_launch + +## Structure + +![autoware_launch](./autoware_launch.drawio.svg) + +## Package Dependencies + +Please see `` in `package.xml`. + +## Usage + +You can use the command as follows at shell script to launch `*.launch.xml` in `launch` directory. + +```bash +ros2 launch autoware_launch autoware.launch.xml map_path:=/path/to/map_folder vehicle_model:=lexus sensor_model:=aip_xx1 +``` diff --git a/launch/autoware_launch/autoware_launch.drawio.svg b/launch/autoware_launch/autoware_launch.drawio.svg new file mode 100644 index 0000000000000..03b8ac1aea42c --- /dev/null +++ b/launch/autoware_launch/autoware_launch.drawio.svg @@ -0,0 +1,4 @@ + + + +
autoware.launch.xml

package: autoware_launch
autoware.launch.xml...
launch name

package: package name
launch name...
ex:
ex:
node name

package: package name
node name...
vehicle_info_launch.py

package: vehicle_launch
vehicle_info_launch.py...
vehicle.launch.xml

package: vehicle_launch
vehicle.launch.xml...
system.launch.xml

package: system_launch
system.launch.xml...
map.launch.py

package: map_launch
map.launch.py...
localization.launch.xml

package: localization_launch
localization.launch.xml...
perception.launch.xml

package: perception_launch
perception.launch.xml...
planning.launch.xml

package: planning_launch
planning.launch.xml...
control.launch.py

package: control_launch
control.launch.py...
awapi_awiv_adapter.launch.xml

package: control_launch
awapi_awiv_adapter.launch.xml...
web_controller.launch.xml

package: control_launch
web_controller.launch.xml...
clock_publisher.launch.xml

package: control_launch
clock_publisher.launch.xml...
rviz2

package: rviz2
rviz2...
planning_simulator.xml

package: autoware_launch
planning_simulator.xml...
vehicle_info_launch.py

package: vehicle_launch
vehicle_info_launch.py...
vehicle.launch.xml

package: vehicle_launch
vehicle.launch.xml...
system.launch.xml

package: system_launch
system.launch.xml...
map.launch.py

package: map_launch
map.launch.py...
planning.launch.xml

package: planning_launch
planning.launch.xml...
control.launch.py

package: control_launch
control.launch.py...
awapi_awiv_adapter.launch.xml

package: control_launch
awapi_awiv_adapter.launch.xml...
web_controller.launch.xml

package: control_launch
web_controller.launch.xml...
clock_publisher.launch.xml

package: control_launch
clock_publisher.launch.xml...
rviz2

package: rviz2
rviz2...
logging_simulator.launch.xml

package: autoware_launch
logging_simulator.launch.xml...
vehicle_info_launch.py

package: vehicle_launch
vehicle_info_launch.py...
vehicle_description.launch.xml

package: vehicle_launch
vehicle_description.launch.xml...
system.launch.xml

package: system_launch
system.launch.xml...
map.launch.py

package: map_launch
map.launch.py...
perception.launch.xml

package: perception_launch
perception.launch.xml...
planning.launch.xml

package: planning_launch
planning.launch.xml...
control.launch.py

package: control_launch
control.launch.py...
web_controller.launch.xml

package: control_launch
web_controller.launch.xml...
rviz2

package: rviz2
rviz2...
$(var vehicle)
$(var vehicle)
True
True
$(var system)
$(var system)
True
True
$(var map)
$(var map)
True
True
sensing.launch.xml

package: sensing_launch
sensing.launch.xml...
sensing.launch.xml

package: sensing_launch
sensing.launch.xml...
$(var sensing)
$(var sensing)
True
True
localization.launch.xml

package: localization_launch
localization.launch.xml...
$(var localization)
$(var localization)
True
True
$(var perception)
$(var perception)
True
True
$(var planning)
$(var planning)
True
True
$(var control)
$(var control)
True
True
simulator.launch.xml

package: simulator_launch
simulator.launch.xml...
simulator.launch.xml

package: simulator_launch
simulator.launch.xml...
Viewer does not support full SVG 1.1
\ No newline at end of file diff --git a/launch/autoware_launch/launch/autoware.launch.xml b/launch/autoware_launch/launch/autoware.launch.xml new file mode 100644 index 0000000000000..1d246ed255331 --- /dev/null +++ b/launch/autoware_launch/launch/autoware.launch.xml @@ -0,0 +1,85 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/autoware_launch/launch/logging_simulator.launch.xml b/launch/autoware_launch/launch/logging_simulator.launch.xml new file mode 100644 index 0000000000000..eddef3476bf37 --- /dev/null +++ b/launch/autoware_launch/launch/logging_simulator.launch.xml @@ -0,0 +1,127 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/autoware_launch/launch/planning_simulator.launch.xml b/launch/autoware_launch/launch/planning_simulator.launch.xml new file mode 100644 index 0000000000000..ee3688a1043de --- /dev/null +++ b/launch/autoware_launch/launch/planning_simulator.launch.xml @@ -0,0 +1,81 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/autoware_launch/launch/pointcloud_container.launch.py b/launch/autoware_launch/launch/pointcloud_container.launch.py new file mode 100644 index 0000000000000..87c46bce69cf7 --- /dev/null +++ b/launch/autoware_launch/launch/pointcloud_container.launch.py @@ -0,0 +1,57 @@ +# Copyright 2021 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer + + +def generate_launch_description(): + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + + pointcloud_container = ComposableNodeContainer( + name=LaunchConfiguration("container_name"), + namespace="/", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=[], + output="screen", + ) + + return LaunchDescription( + [ + add_launch_arg("use_multithread", "false"), + add_launch_arg("container_name", "pointcloud_container"), + set_container_executable, + set_container_mt_executable, + pointcloud_container, + ] + ) diff --git a/launch/autoware_launch/package.xml b/launch/autoware_launch/package.xml new file mode 100644 index 0000000000000..7fa93239afd0f --- /dev/null +++ b/launch/autoware_launch/package.xml @@ -0,0 +1,33 @@ + + + autoware_launch + 0.1.0 + The autoware_launch package + + Yukihiro Saito + Apache License 2.0 + + ament_cmake_auto + + control_launch + global_parameter_loader + localization_launch + map_launch + perception_launch + planning_launch + python3-bson + python3-tornado + rviz2 + sensing_launch + simulator_launch + system_launch + vehicle_launch + web_controller + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/launch/autoware_launch/rviz/autoware.rviz b/launch/autoware_launch/rviz/autoware.rviz new file mode 100644 index 0000000000000..4cf1b192fd95e --- /dev/null +++ b/launch/autoware_launch/rviz/autoware.rviz @@ -0,0 +1,1546 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.557669460773468 + Tree Height: 397 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: ~ + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: ~ + Name: Views + Splitter Ratio: 0.5 + - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel + Name: InitialPoseButtonPanel + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +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: + - Class: rviz_plugins/SteeringAngle + Enabled: true + Left: 128 + Length: 256 + Name: SteeringAngle + Scale: 17 + Text Color: 25; 255; 240 + Top: 128 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /vehicle/status/steering_status + Value: true + Value height offset: 0 + - Class: rviz_plugins/ConsoleMeter + Enabled: true + Left: 512 + Length: 256 + Name: ConsoleMeter + Scale: 3 + Text Color: 25; 255; 240 + Top: 128 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /vehicle/status/velocity_status + Value: true + Value height offset: 0 + - Alpha: 0.999 + Class: rviz_plugins/VelocityHistory + Color Border Vel Max: 3 + Constant Color: + Color: 255; 255; 255 + Value: true + Enabled: true + Name: VelocityHistory + Scale: 0.30000001192092896 + Timeout: 10 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /vehicle/status/velocity_status + Value: true + - Alpha: 0.30000001192092896 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + 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: 0.999 + Show Axes: false + Show Trail: false + Value: true + camera0/camera_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + camera0/camera_optical_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + camera1/camera_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + camera1/camera_optical_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + camera2/camera_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + camera2/camera_optical_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + camera3/camera_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + camera3/camera_optical_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + camera4/camera_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + camera4/camera_optical_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + camera5/camera_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + camera5/camera_optical_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + gnss_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + livox_front_left: + Alpha: 0.999 + Show Axes: false + Show Trail: false + livox_front_left_base_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + livox_front_right: + Alpha: 0.999 + Show Axes: false + Show Trail: false + livox_front_right_base_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + sensor_kit_base_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + tamagawa/imu_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + traffic_light_left_camera/camera_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + traffic_light_left_camera/camera_optical_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + traffic_light_right_camera/camera_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + traffic_light_right_camera/camera_optical_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + velodyne_left: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + velodyne_left_base_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + velodyne_rear: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + velodyne_rear_base_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + velodyne_right: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + velodyne_right_base_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + velodyne_top: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + velodyne_top_base_link: + Alpha: 0.999 + Show Axes: false + Show Trail: false + Value: true + 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.01 + Min Wave Alpha: 0.01 + Name: PolarGridDisplay + Reference Frame: base_link + Value: true + Wave Color: 255; 255; 255 + Wave Velocity: 40 + - Class: rviz_plugins/MaxVelocity + Enabled: true + Left: 595 + Length: 96 + Name: MaxVelocity + Text Color: 255; 255; 255 + Top: 280 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/current_max_velocity + Value: true + - Class: rviz_plugins/TurnSignal + Enabled: true + Height: 256 + Left: 196 + Name: TurnSignal + Top: 350 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /vehicle/status/turn_indicators_status + Value: true + Width: 512 + 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: true + 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: true + Size (Pixels): 1 + Size (m): 0.02 + Style: Points + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map/pointcloud_map + Use Fixed Frame: true + Use rainbow: false + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: Lanelet2VectorMap + Namespaces: + center_lane_line: false + crosswalk_lanelets: true + lanelet direction: true + lanelet_id: false + left_lane_bound: true + parking_lots: true + parking_space: true + pedestrian_marking: true + right_lane_bound: true + road_lanelets: false + stop_lines: true + shoulder_center_lane_line: false + shoulder_left_lane_bound: true + shoulder_right_lane_bound: true + shoulder_road_lanelets: false + traffic_light: true + traffic_light_id: false + traffic_light_triangle: true + walkway_lanelets: true + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map/vector_map_marker + Value: true + Enabled: true + Name: Map + - Class: rviz_common/Group + Displays: + - Class: rviz_common/Group + Displays: + - Alpha: 0.4 + 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: true + Size (Pixels): 1 + Size (m): 0.02 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /sensing/lidar/concatenated/pointcloud + Use Fixed Frame: false + Use rainbow: true + Value: true + - Alpha: 0.999 + Class: rviz_default_plugins/Polygon + Color: 25; 255; 0 + Enabled: false + Name: MeasurementRange + Topic: + Depth: 5 + Durability Policy: Volatile + 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 + 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.999 + 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 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/initial_pose_with_covariance + Value: true + - Alpha: 0.999 + 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 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/pose_with_covariance + Value: true + - Buffer Size: 200 + Class: rviz_plugins::PoseHistory + Enabled: false + Line: + Color: 170; 255; 127 + Value: true + Width: 0.10000000149011612 + Alpha: 0.999 + Name: PoseHistory + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/pose + Value: true + - Alpha: 0.999 + 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: true + Size (Pixels): 10 + Size (m): 0.02 + Style: Squares + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/util/downsample/pointcloud + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 0.999 + 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: true + Size (Pixels): 10 + Size (m): 0.02 + Style: Squares + Topic: + Depth: 5 + Durability Policy: Volatile + 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: + Color: 0; 255; 255 + Value: true + Width: 0.10000000149011612 + Alpha: 0.999 + Name: PoseHistory + Topic: + Depth: 5 + Durability Policy: Volatile + 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.999 + 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: true + Size (Pixels): 3 + Size (m): 0.02 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + 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: + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display 3d polygon: 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 + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: DetectedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + 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.999 + Color: 255; 255; 255 + Value: true + Enabled: false + Name: Detection + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/TrackedObjects + Display 3d polygon: 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 + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: TrackedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/object_recognition/tracking/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 + Value: true + Enabled: false + Name: Tracking + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/PredictedObjects + Display 3d polygon: 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 + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: PredictedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/object_recognition/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 + Value: true + Enabled: true + Name: Prediction + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/Image + Enabled: true + 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: Reliable + Value: /perception/traffic_light_recognition/debug/rois + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MapBasedDetectionResult + Namespaces: {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers + Value: true + Enabled: true + Name: TrafficLight + Enabled: true + Name: Perception + - Class: rviz_common/Group + Displays: + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: RouteArea + Namespaces: + goal_lanelets: true + left_lane_bound: false + right_lane_bound: false + route_lanelets: true + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/mission_planning/route_marker + Value: true + - Alpha: 0.999 + 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 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/mission_planning/echo_back_goal_pose + Value: true + 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 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/trajectory + Value: true + View Path: + Alpha: 0.999 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 0.999 + 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 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/path + Value: true + View Path: + Alpha: 0.4000000059604645 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 0.4000000059604645 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: true + - 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: true + Name: Crosswalk + Namespaces: + collision line: false + collision point: false + factor_text: true + slow factor_text: true + slow point: false + slow polygon line: false + slow virtual_wall: true + stop point: false + stop polygon line: false + stop_virtual_wall: true + walkway stop judge range: false + 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: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: Intersection + Namespaces: + candidate_collision_ego_lane_polygon: false + candidate_collision_object_polygons: false + conflicting_targets: false + detection_area: false + ego_lane: false + factor_text: true + judge_point_pose_line: false + path_raw: false + spline: false + stop_point_pose_line: false + stop_virtual_wall: true + stuck_vehicle_detect_area: false + stuck_targets: false + 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: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: Blind Spot + Namespaces: + conflict_area_for_blind_spot: false + conflicting_targets: false + detection_area: false + detection_area_for_blind_spot: false + factor_text: true + judge_point_pose_line: false + path_raw: false + stop_virtual_wall: true + spline: false + stop_point_pose_line: false + 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: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: TrafficLight + Namespaces: + dead line factor_text: false + dead line virtual_wall: false + factor_text: true + stop_virtual_wall: true + 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: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualTrafficLight + Namespaces: + end_lines: false + instrument_center: false + instrument_id: false + start_line: false + stop_factor_text: true + stop_line: false + stop_virtual_wall: true + 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: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: StopLine + Namespaces: + factor_text: true + stop_virtual_wall: true + 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: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: DetectionArea + Namespaces: + detection_area_correspondence: false + detection_area_id: false + detection_area_polygon: false + factor_text: true + obstacles: false + stop_virtual_wall: true + 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: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: OcclusionSpot + Namespaces: + arrow: false + occlusion spot slow down: true + collision: false + info_obstacle: false + obstacle: false + sidewalk: false + slow factor_text: true + 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: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: NoStoppingArea + Namespaces: + no_stopping_area_correspondence: false + no_stopping_area_id: false + no_stopping_area_polygon: false + stuck_vehicle_detect_area: false + stop_line_detect_area: false + stuck_points: false + stop_factor_text: true + stop_virtual_wall: true + 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: true + - Class: rviz_plugins/Path + Color Border Vel Max: 3 + Enabled: true + Name: PathChangeCandidate + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/output/path_candidate + Value: true + View Path: + Alpha: 0.30000001192092896 + Color: 115; 210; 22 + Constant Color: true + Value: true + Width: 2 + View Velocity: + Alpha: 0.30000001192092896 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + 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 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/trajectory + Value: false + View Path: + Alpha: 0.999 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 0.999 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: ObstacleStop + Namespaces: + collision_polygons: false + detection_polygons: false + slow_down_polygons: false + slow_down_detection_polygons: false + stop_obstacle_point: false + stop_obstacle_text: false + slow_down_obstacle_point: false + slow_down_obstacle_text: false + slow_down_start_virtual_wall: false + slow_down_start_factor_text: false + slow_down_end_virtual_wall: false + slow_down_end_factor_text: false + slow_down_end: false + stop_virtual_wall: true + stop_factor_text: true + slow_down_virtual_wall: true + slow_down_factor_text: true + 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: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: SurroundObstacleCheck + Namespaces: + factor_text: true + virtual_wall: true + obstacle_point: true + no_start_obstacle_text: true + 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 + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: ObstacleAvoidance + Namespaces: + avoiding_objects: false + base_bounds_line: false + bounds_candidate_base_text: false + bounds_candidate_for_base: false + bounds_candidate_for_top: false + bounds_candidate_top_text: false + constrain_rect: false + constrain_rect_text: false + constrain_rect_location: false + current_vehicle_footprint: false + extending_constrain_rect: false + extending_constrain_rect_text: false + extending_constrain_rect_location: false + fixed_mpt_points: false + fixed_points_for_extending: false + fixed_points_marker: false + interpolated_points_for_extending: false + interpolated_points_marker: false + interpolated_points_text_marker: false + non_fixed_points_for_extending: false + non_fixed_points_marker: false + num_vehicle_footprint: false + optimized_points_marker: false + optimized_points_text_marker: false + smoothed_points_text: false + straight_points_marker: false + top_bounds_line: false + mid_bounds_line: false + vehicle_footprint: false + virtual_wall: true + virtual_wall_text: true + 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: true + 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 + 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.999 + 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 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/parking/freespace_planner/debug/partial_pose_array + Value: true + - Alpha: 0.999 + 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 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/parking/freespace_planner/debug/pose_array + Value: true + Enabled: true + Name: Parking + Enabled: true + Name: ScenarioPlanning + 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 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /control/trajectory_follower/lateral/predicted_trajectory + Value: true + View Path: + Alpha: 1 + Color: 255; 255; 255 + Constant Color: true + Value: true + Width: 0.05000000074505806 + 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/pure_pursuit/debug/markers + Value: false + Enabled: true + Name: Control + Enabled: true + Global Options: + Background Color: 10; 10; 10 + Default Light: true + 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 + Theta std deviation: 0.2617993950843811 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/mission_planning/goal + - Class: rviz_plugins/PedestrianInitialPoseTool + Pose Topic: /simulation/dummy_perception_publisher/object_info + 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 + - Class: rviz_plugins/CarInitialPoseTool + Pose Topic: /simulation/dummy_perception_publisher/object_info + Theta std deviation: 0.0872664600610733 + Velocity: 3 + 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 + 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: viewer + 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: + Displays: + collapsed: false + Height: 1565 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000329000006fffc020000000cfb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000006e000001fb0000018200fffffffc00000275000002840000016c01000039fa000000000100000002fb0000000a0056006900650077007301000000000000033c0000015f00fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000000ffffffff0000010b00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000682000000eb0000000000000000fb0000000a0049006d0061006700650100000505000002680000002600fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de000000de00fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de000000de00ffffff000000010000015f000006fffc0200000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000e7a0000005afc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000e7a0000005afc0100000002fb0000000800540069006d0065010000000000000e7a0000057100fffffffb0000000800540069006d0065010000000000000450000000000000000000000b45000006ff00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 2813 + X: 67 + Y: 27 diff --git a/launch/autoware_launch/rviz/image/autoware.png b/launch/autoware_launch/rviz/image/autoware.png new file mode 100644 index 0000000000000..cf2d1e8eff355 Binary files /dev/null and b/launch/autoware_launch/rviz/image/autoware.png differ