diff --git a/README.md b/README.md index 1bb62f4..88f0ec4 100644 --- a/README.md +++ b/README.md @@ -81,7 +81,7 @@ source ~/ros2_ws/install/setup.sh #### 2. Launch the simulation ```bash -ros2 launch ardupilot_gz_bringup iris_runway.launch.py +ros2 launch ardupilot_gz_bringup iris_runway.launch.py rviz:=true use_gz_tf:=true ``` #### 3. Launch a GCS (MAVPorxy) @@ -120,9 +120,19 @@ Here's a list of all the additional use cases from this repository: This simulation has an iris copter equipped with a 360 degrees 2d lidar in a maze world. ```bash -ros2 launch ardupilot_gz_bringup iris_maze.launch.py +ros2 launch ardupilot_gz_bringup iris_maze.launch.py rviz:=true use_gz_tf:=true ``` +### 2. Wild Thumper playpen + +This simulation includes a skid-steer rover equipped with a 2d lidar in a playpen world. + + +```bash +ros2 launch ardupilot_gz_bringup wildthumper_playpen.launch.py rviz:=true use_gz_tf:=true +``` + + ## Notes ### 1. Additional dependencies diff --git a/ardupilot_gz_bringup/config/wildthumper_bridge.yaml b/ardupilot_gz_bringup/config/wildthumper_bridge.yaml new file mode 100644 index 0000000..2cc3d33 --- /dev/null +++ b/ardupilot_gz_bringup/config/wildthumper_bridge.yaml @@ -0,0 +1,50 @@ +--- +- ros_topic_name: "clock" + gz_topic_name: "/clock" + ros_type_name: "rosgraph_msgs/msg/Clock" + gz_type_name: "gz.msgs.Clock" + direction: GZ_TO_ROS +- ros_topic_name: "joint_states" + gz_topic_name: "/world/playpen/model/wildthumper/joint_state" + ros_type_name: "sensor_msgs/msg/JointState" + gz_type_name: "gz.msgs.Model" + direction: GZ_TO_ROS +- ros_topic_name: "odometry" + gz_topic_name: "/model/wildthumper/odometry" + ros_type_name: "nav_msgs/msg/Odometry" + gz_type_name: "gz.msgs.Odometry" + direction: GZ_TO_ROS +- ros_topic_name: "gz/tf" + gz_topic_name: "/model/wildthumper/pose" + ros_type_name: "tf2_msgs/msg/TFMessage" + gz_type_name: "gz.msgs.Pose_V" + direction: GZ_TO_ROS +- ros_topic_name: "gz/tf_static" + gz_topic_name: "/model/wildthumper/pose_static" + ros_type_name: "tf2_msgs/msg/TFMessage" + gz_type_name: "gz.msgs.Pose_V" + direction: GZ_TO_ROS + +- ros_topic_name: "imu" + gz_topic_name: "/world/playpen/model/wildthumper/link/imu_link/sensor/imu_sensor/imu" + ros_type_name: "sensor_msgs/msg/Imu" + gz_type_name: "gz.msgs.IMU" + direction: GZ_TO_ROS + +- ros_topic_name: "magnetometer" + gz_topic_name: "/world/playpen/model/wildthumper/link/base_link/sensor/magnetometer_sensor/magnetometer" + ros_type_name: "sensor_msgs/msg/MagneticField" + gz_type_name: "gz.msgs.Magnetometer" + direction: GZ_TO_ROS + +- ros_topic_name: "navsat" + gz_topic_name: "/world/playpen/model/wildthumper/link/base_link/sensor/navsat_sensor/navsat" + ros_type_name: "sensor_msgs/msg/NavSatFix" + gz_type_name: "gz.msgs.NavSat" + direction: GZ_TO_ROS + +- ros_topic_name: "battery" + gz_topic_name: "/model/wildthumper/battery/linear_battery/state" + ros_type_name: "sensor_msgs/msg/BatteryState" + gz_type_name: "gz.msgs.BatteryState" + direction: GZ_TO_ROS diff --git a/ardupilot_gz_bringup/launch/robots/wildthumper.launch.py b/ardupilot_gz_bringup/launch/robots/wildthumper.launch.py new file mode 100644 index 0000000..6651f6c --- /dev/null +++ b/ardupilot_gz_bringup/launch/robots/wildthumper.launch.py @@ -0,0 +1,198 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +""" +Launch an wild thumper rover in Gazebo and Rviz. + +ros2 launch ardupilot_sitl sitl_dds_udp.launch.py +transport:=udp4 +refs:=$(ros2 pkg prefix ardupilot_sitl) + /share/ardupilot_sitl/config/dds_xrce_profile.xml +port:=2019 +synthetic_clock:=True +wipe:=False +model:=json +speedup:=1 +slave:=0 +instance:=0 +defaults:=$(ros2 pkg prefix ardupilot_sitl) + /share/ardupilot_sitl/config/default_params/rover-skid.parm, + $(ros2 pkg prefix ardupilot_sitl) + /share/ardupilot_sitl/config/default_params/dds_udp.parm +sim_address:=127.0.0.1 +master:=tcp:127.0.0.1:5760 +sitl:=127.0.0.1:5501 +""" +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.actions import RegisterEventHandler + +from launch.conditions import IfCondition + +from launch.event_handlers import OnProcessStart + +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch.substitutions import PathJoinSubstitution + +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + + +def generate_launch_description(): + """Generate a launch description for a wild thumper rover.""" + pkg_ardupilot_sitl = get_package_share_directory("ardupilot_sitl") + pkg_ardupilot_sitl_models = get_package_share_directory("ardupilot_sitl_models") + pkg_project_bringup = get_package_share_directory("ardupilot_gz_bringup") + + # Include component launch files. + sitl_dds = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "sitl_dds_udp.launch.py", + ] + ), + ] + ), + launch_arguments={ + "transport": "udp4", + "refs": PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "config", + "dds_xrce_profile.xml", + ] + ), + "port": "2019", + "command": "ardurover", + "synthetic_clock": "True", + "wipe": "False", + "model": "json", + "speedup": "1", + "slave": "0", + "instance": "0", + "defaults": os.path.join( + pkg_ardupilot_sitl, + "config", + "default_params", + "rover-skid.parm", + ) + + "," + + os.path.join( + pkg_ardupilot_sitl, + "config", + "default_params", + "dds_udp.parm", + ), + "sim_address": "127.0.0.1", + "master": "tcp:127.0.0.1:5760", + "sitl": "127.0.0.1:5501", + }.items(), + ) + + # Robot description. + + # Ensure `SDF_PATH` is populated as `sdformat_urdf`` uses this rather + # than `GZ_SIM_RESOURCE_PATH` to locate resources. + if "GZ_SIM_RESOURCE_PATH" in os.environ: + gz_sim_resource_path = os.environ["GZ_SIM_RESOURCE_PATH"] + + if "SDF_PATH" in os.environ: + sdf_path = os.environ["SDF_PATH"] + os.environ["SDF_PATH"] = sdf_path + ":" + gz_sim_resource_path + else: + os.environ["SDF_PATH"] = gz_sim_resource_path + + # Load SDF file. + sdf_file = os.path.join( + pkg_ardupilot_sitl_models, "models", "wildthumper", "model.sdf" + ) + with open(sdf_file, "r") as infp: + robot_desc = infp.read() + + # substitute `models://` with `package://ardupilot_sitl_models/models/` + # for sdformat_urdf plugin used by robot_state_publisher + robot_desc = robot_desc.replace( + "model://wildthumper", + "package://ardupilot_sitl_models/models/wildthumper") + + # Publish /tf and /tf_static. + robot_state_publisher = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + name="robot_state_publisher", + output="both", + parameters=[ + {"robot_description": robot_desc}, + {"frame_prefix": ""}, + ], + ) + + # Bridge. + bridge = Node( + package="ros_gz_bridge", + executable="parameter_bridge", + parameters=[ + { + "config_file": os.path.join( + pkg_project_bringup, "config", "wildthumper_bridge.yaml" + ), + "qos_overrides./tf_static.publisher.durability": "transient_local", + } + ], + output="screen", + ) + + # Relay - use instead of transform when Gazebo is only publishing odom -> base_link + topic_tools_tf = Node( + package="topic_tools", + executable="relay", + arguments=[ + "/gz/tf", + "/tf", + ], + output="screen", + respawn=False, + condition=IfCondition(LaunchConfiguration("use_gz_tf")), + ) + + return LaunchDescription( + [ + DeclareLaunchArgument( + "use_gz_tf", default_value="true", description="Use Gazebo TF." + ), + sitl_dds, + robot_state_publisher, + bridge, + RegisterEventHandler( + OnProcessStart( + target_action=bridge, + on_start=[ + topic_tools_tf + ] + ) + ), + ] + ) diff --git a/ardupilot_gz_bringup/launch/wildthumper_playpen.launch.py b/ardupilot_gz_bringup/launch/wildthumper_playpen.launch.py new file mode 100644 index 0000000..f8cec89 --- /dev/null +++ b/ardupilot_gz_bringup/launch/wildthumper_playpen.launch.py @@ -0,0 +1,108 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +# Adapted from https://github.com/gazebosim/ros_gz_project_template +# +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# 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. + +"""Launch a wildthumper rover in the playpen world.""" +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch.substitutions import PathJoinSubstitution + +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + """Generate a launch description for a wildthumper rover.""" + pkg_ardupilot_sitl_models = get_package_share_directory("ardupilot_sitl_models") + pkg_project_bringup = get_package_share_directory("ardupilot_gz_bringup") + pkg_project_gazebo = get_package_share_directory("ardupilot_gz_gazebo") + pkg_ros_gz_sim = get_package_share_directory("ros_gz_sim") + + # Wild Thumper rover. + rover = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_gz_bringup"), + "launch", + "robots", + "wildthumper.launch.py", + ] + ), + ] + ) + ) + + # Gazebo. + gz_sim_server = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, "launch", "gz_sim.launch.py") + ), + launch_arguments={ + "gz_args": "-v4 -s -r " + + os.path.join(pkg_ardupilot_sitl_models, "worlds", "wildthumper_playpen.sdf") + }.items(), + ) + + gz_sim_gui = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, "launch", "gz_sim.launch.py") + ), + launch_arguments={"gz_args": "-v4 -g"}.items(), + ) + + # RViz. + rviz = Node( + package="rviz2", + executable="rviz2", + arguments=["-d", os.path.join(pkg_project_bringup, "rviz", "wildthumper.rviz")], + condition=IfCondition(LaunchConfiguration("rviz")), + ) + + return LaunchDescription( + [ + DeclareLaunchArgument( + "rviz", default_value="true", description="Open RViz." + ), + gz_sim_server, + gz_sim_gui, + rover, + rviz, + ] + ) diff --git a/ardupilot_gz_bringup/package.xml b/ardupilot_gz_bringup/package.xml index fdc2f96..8b8e8ac 100644 --- a/ardupilot_gz_bringup/package.xml +++ b/ardupilot_gz_bringup/package.xml @@ -12,10 +12,13 @@ ardupilot_gz_description ardupilot_gz_gazebo ardupilot_sitl + ardupilot_sitl_models launch launch_ros ros_gz_sim + ros_gz_bridge robot_state_publisher + sdformat_urdf topic_tools ament_cmake_pytest ament_lint_auto diff --git a/ardupilot_gz_bringup/rviz/wildthumper.rviz b/ardupilot_gz_bringup/rviz/wildthumper.rviz new file mode 100644 index 0000000..c6033e7 --- /dev/null +++ b/ardupilot_gz_bringup/rviz/wildthumper.rviz @@ -0,0 +1,395 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /WildThumper1 + - /WildThumper1/Odometry1/Shape1 + Splitter Ratio: 0.5 + Tree Height: 587 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Class: rviz_common/Group + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + 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: true + - Class: rviz_default_plugins/Axes + Enabled: true + Length: 10 + Name: Axes + Radius: 0.05000000074505806 + Reference Frame: + Value: true + - Alpha: 1 + 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 + front_left_motor_asm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_left_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_right_motor_asm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_right_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_small_chassis_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_wheel_chassis_short_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + mid_left_motor_asm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + mid_left_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + mid_right_motor_asm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + mid_right_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + mid_wheel_chassis_long_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_left_motor_asm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_left_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_right_motor_asm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_right_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_small_chassis_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_wheel_chassis_short_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + top_chassis_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + base_link: + Value: true + front_left_motor_asm_link: + Value: true + front_left_wheel_link: + Value: true + front_right_motor_asm_link: + Value: true + front_right_wheel_link: + Value: true + front_small_chassis_link: + Value: true + front_wheel_chassis_short_link: + Value: true + imu_link: + Value: true + mid_left_motor_asm_link: + Value: true + mid_left_wheel_link: + Value: true + mid_right_motor_asm_link: + Value: true + mid_right_wheel_link: + Value: true + mid_wheel_chassis_long_link: + Value: true + odom: + Value: true + rear_left_motor_asm_link: + Value: true + rear_left_wheel_link: + Value: true + rear_right_motor_asm_link: + Value: true + rear_right_wheel_link: + Value: true + rear_small_chassis_link: + Value: true + rear_wheel_chassis_short_link: + Value: true + top_chassis_link: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + odom: + base_link: + front_small_chassis_link: + {} + front_wheel_chassis_short_link: + front_left_motor_asm_link: + front_left_wheel_link: + {} + front_right_motor_asm_link: + front_right_wheel_link: + {} + imu_link: + {} + mid_wheel_chassis_long_link: + mid_left_motor_asm_link: + mid_left_wheel_link: + {} + mid_right_motor_asm_link: + mid_right_wheel_link: + {} + rear_small_chassis_link: + {} + rear_wheel_chassis_short_link: + rear_left_motor_asm_link: + rear_left_wheel_link: + {} + rear_right_motor_asm_link: + rear_right_wheel_link: + {} + top_chassis_link: + {} + Update Interval: 0 + Value: true + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + 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: true + Keep: 500 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 255 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Arrow + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /odometry + Value: true + Enabled: true + Name: WildThumper + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: odom + 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: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.658808708190918 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.7260509133338928 + Y: 0.23755063116550446 + Z: -0.10189704596996307 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.4597952961921692 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.6335575580596924 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 800 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000001630000029afc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006200fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002c0000029a000000e300fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065000000019c0000012a0000000000000000000000010000010f0000029bfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002c0000029b000000c600fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000023d00fffffffb0000000800540069006d006501000000000000045000000000000000000000034c0000029a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 0 + Y: 38