This commit is contained in:
acki
2024-12-14 21:59:45 -05:00
parent b3efb75789
commit 8f10d4dbbd
16 changed files with 1676 additions and 22 deletions

1
.gitignore vendored
View File

@@ -105,3 +105,4 @@ AMENT_IGNORE
.vscode
.cache
src/modelec/src

View File

@@ -93,6 +93,21 @@ target_include_directories(button_gpio_controller PUBLIC
$<INSTALL_INTERFACE:include>
)
add_executable(lidar_controller src/lidar_controller.cpp)
ament_target_dependencies(lidar_controller rclcpp std_msgs sensor_msgs modelec_interface)
target_include_directories(lidar_controller PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)
# Enable testing and linting
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
set(ament_cmake_copyright_FOUND TRUE)
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
# Install targets
install(TARGETS
usb_arduino_listener
@@ -112,18 +127,10 @@ install(DIRECTORY include/
DESTINATION include/
)
# Install launch files
install(DIRECTORY launch/
DESTINATION share/${PROJECT_NAME}/launch
install(
DIRECTORY config description launch worlds
DESTINATION share/${PROJECT_NAME}
)
# Enable testing and linting
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
set(ament_cmake_copyright_FOUND TRUE)
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
# Finalize package
ament_package()

View File

@@ -0,0 +1,48 @@
- 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
# gz topic published by Sensors plugin
- ros_topic_name: "scan"
gz_topic_name: "scan"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "gz.msgs.LaserScan"
direction: GZ_TO_ROS
# gz topic published by Sensors plugin (Camera)
- ros_topic_name: "camera/camera_info"
gz_topic_name: "camera/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "gz.msgs.CameraInfo"
direction: GZ_TO_ROS
# gz topic published by DiffDrive plugin
- ros_topic_name: "odom"
gz_topic_name: "odom"
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "gz.msgs.Odometry"
direction: GZ_TO_ROS
# gz topic published by DiffDrive plugin
- ros_topic_name: "tf"
gz_topic_name: "tf"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "gz.msgs.Pose_V"
direction: GZ_TO_ROS
# gz topic subscribed to by DiffDrive plugin
- ros_topic_name: "diff_cont/cmd_vel_unstamped"
gz_topic_name: "cmd_vel"
ros_type_name: "geometry_msgs/msg/Twist"
gz_type_name: "gz.msgs.Twist"
direction: ROS_TO_GZ
# gz topic published by JointState plugin
- ros_topic_name: "joint_states"
gz_topic_name: "joint_states"
ros_type_name: "sensor_msgs/msg/JointState"
gz_type_name: "gz.msgs.Model"
direction: GZ_TO_ROS

View File

@@ -0,0 +1,216 @@
Panels:
- Class: rviz_common/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 555
- 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:
- 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: <Fixed Frame>
Value: true
- Class: rviz_default_plugins/TF
Enabled: true
Filter (blacklist): ""
Filter (whitelist): ""
Frame Timeout: 15
Frames:
All Enabled: true
base_link:
Value: true
caster_wheel:
Value: true
chassis:
Value: true
left_wheel:
Value: true
right_wheel:
Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
base_link:
chassis:
caster_wheel:
{}
left_wheel:
{}
right_wheel:
{}
Update Interval: 0
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
caster_wheel:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
chassis:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
left_wheel:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
right_wheel:
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
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: base_link
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: 1.2347779273986816
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: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.3903981149196625
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.6003981232643127
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000002b4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002b4000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000002b4000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000025300fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 28
Y: 28

View File

@@ -0,0 +1,42 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<gazebo>
<plugin name="gz::sim::systems::DiffDrive" filename="gz-sim-diff-drive-system">
<!-- Wheel Information -->
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>0.297</wheel_separation>
<wheel_radius>0.033</wheel_radius>
<!-- Limits -->
<!-- <max_wheel_torque>200</max_wheel_torque> -->
<max_linear_acceleration>0.33</max_linear_acceleration>
<!-- Input -->
<topic>cmd_vel</topic>
<!-- Output -->
<frame_id>odom</frame_id>
<child_frame_id>base_link</child_frame_id>
<odom_topic>odom</odom_topic>
<odom_publisher_frequency>30</odom_publisher_frequency>
<tf_topic>/tf</tf_topic>
</plugin>
<plugin filename="gz-sim-joint-state-publisher-system"
name="gz::sim::systems::JointStatePublisher">
<topic>joint_states</topic>
<joint_name>left_wheel_joint</joint_name>
<joint_name>right_wheel_joint</joint_name>
</plugin>
</gazebo>
</robot>

View File

@@ -0,0 +1,40 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
<!-- Specify some standard inertial calculations https://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<!-- These make use of xacro's mathematical functionality -->
<xacro:macro name="inertial_sphere" params="mass radius *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(2/5) * mass * (radius*radius)}" ixy="0.0" ixz="0.0"
iyy="${(2/5) * mass * (radius*radius)}" iyz="0.0"
izz="${(2/5) * mass * (radius*radius)}" />
</inertial>
</xacro:macro>
<xacro:macro name="inertial_box" params="mass x y z *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(1/12) * mass * (y*y+z*z)}" ixy="0.0" ixz="0.0"
iyy="${(1/12) * mass * (x*x+z*z)}" iyz="0.0"
izz="${(1/12) * mass * (x*x+y*y)}" />
</inertial>
</xacro:macro>
<xacro:macro name="inertial_cylinder" params="mass length radius *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(1/12) * mass * (3*radius*radius + length*length)}" ixy="0.0" ixz="0.0"
iyy="${(1/12) * mass * (3*radius*radius + length*length)}" iyz="0.0"
izz="${(1/2) * mass * (radius*radius)}" />
</inertial>
</xacro:macro>
</robot>

View File

@@ -0,0 +1,8 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="robot">
<xacro:include filename="robot_core.xacro" />
<xacro:include filename="gazebo_control.xacro" />
</robot>

View File

@@ -0,0 +1,156 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
<xacro:include filename="inertial_macros.xacro"/>
<material name="white">
<color rgba="1 1 1 1" />
</material>
<material name="orange">
<color rgba="1 0.3 0.1 1"/>
</material>
<material name="blue">
<color rgba="0.2 0.2 1 1"/>
</material>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<!-- BASE LINK -->
<link name="base_link">
</link>
<!-- CHASSIS LINK -->
<joint name="chassis_joint" type="fixed">
<parent link="base_link"/>
<child link="chassis"/>
<origin xyz="-0.1 0 0"/>
</joint>
<link name="chassis">
<visual>
<origin xyz="0.15 0 0.075"/>
<geometry>
<box size="0.3 0.3 0.15"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin xyz="0.15 0 0.075"/>
<geometry>
<box size="0.3 0.3 0.15"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="0.3" y="0.3" z="0.15">
<origin xyz="0.15 0 0.075" rpy="0 0 0"/>
</xacro:inertial_box>
</link>
<gazebo reference="chassis">
<material>Gazebo/White</material>
</gazebo>
<!-- LEFT WHEEL LINK -->
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0 0.175 0" rpy="-${pi/2} 0 0" />
<axis xyz="0 0 1"/>
</joint>
<link name="left_wheel">
<visual>
<geometry>
<cylinder radius="0.05" length="0.04"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.05" length="0.04"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.04" radius="0.05">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="left_wheel">
<material>Gazebo/Blue</material>
</gazebo>
<!-- RIGHT WHEEL LINK -->
<joint name="right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="0 -0.175 0" rpy="${pi/2} 0 0" />
<axis xyz="0 0 -1"/>
</joint>
<link name="right_wheel">
<visual>
<geometry>
<cylinder radius="0.05" length="0.04"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.05" length="0.04"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.04" radius="0.05">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="right_wheel">
<material>Gazebo/Blue</material>
</gazebo>
<!-- CASTER WHEEL LINK -->
<joint name="caster_wheel_joint" type="fixed">
<parent link="chassis"/>
<child link="caster_wheel"/>
<origin xyz="0.24 0 0"/>
</joint>
<link name="caster_wheel">
<visual>
<geometry>
<sphere radius="0.05"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<sphere radius="0.05"/>
</geometry>
</collision>
<xacro:inertial_sphere mass="0.1" radius="0.05">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_sphere>
</link>
<gazebo reference="caster_wheel">
<material>Gazebo/Black</material>
<mu1 value="0.001"/>
<mu2 value="0.001"/>
</gazebo>
</robot>

View File

@@ -0,0 +1,18 @@
#pragma once
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/subscription.hpp>
#include <sensor_msgs/msg/laser_scan.hpp>
namespace Modelec {
class LidarController : public rclcpp::Node {
private:
public:
LidarController();
private:
rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr subscription_;
void processLidarData(const sensor_msgs::msg::LaserScan::SharedPtr msg);
};
}

View File

@@ -0,0 +1,74 @@
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
# Include the robot_state_publisher launch file, provided by our own package. Force sim time to be enabled
# !!! MAKE SURE YOU SET THE PACKAGE NAME CORRECTLY !!!
package_name='modelec' #<--- CHANGE ME
rsp = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory(package_name),'launch','rsp.launch.py'
)]), launch_arguments={'use_sim_time': 'true'}.items()
)
default_world = os.path.join(
get_package_share_directory(package_name),
'worlds',
'empty.world'
)
world = LaunchConfiguration('world')
world_arg = DeclareLaunchArgument(
'world',
default_value=default_world,
description='World to load'
)
# Include the Gazebo launch file, provided by the gazebo_ros package
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('ros_gz_sim'), 'launch', 'gz_sim.launch.py')]),
launch_arguments={'gz_args': ['-r -v4 ', world], 'on_exit_shutdown': 'true'}.items()
)
# Run the spawner node from the gazebo_ros package. The entity name doesn't really matter if you only have a single robot.
spawn_entity = Node(package='ros_gz_sim', executable='create',
arguments=['-topic', 'robot_description',
'-name', 'my_bot',
'-z', '0.1'],
output='screen')
bridge_params = os.path.join(get_package_share_directory(package_name),'config','gz_bridge.yaml')
ros_gz_bridge = Node(
package="ros_gz_bridge",
executable="parameter_bridge",
arguments=[
'--ros-args',
'-p',
f'config_file:={bridge_params}',
]
)
# Launch them all!
return LaunchDescription([
rsp,
world_arg,
gazebo,
spawn_entity,
ros_gz_bridge,
])

View File

@@ -0,0 +1,41 @@
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument
from launch_ros.actions import Node
import xacro
def generate_launch_description():
# Check if we're told to use sim time
use_sim_time = LaunchConfiguration('use_sim_time')
# Process the URDF file
pkg_path = os.path.join(get_package_share_directory('modelec'))
xacro_file = os.path.join(pkg_path,'description','robot.urdf.xacro')
robot_description_config = xacro.process_file(xacro_file)
# Create a robot_state_publisher node
params = {'robot_description': robot_description_config.toxml(), 'use_sim_time': use_sim_time}
node_robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[params]
)
# Launch!
return LaunchDescription([
DeclareLaunchArgument(
'use_sim_time',
default_value='false',
description='Use sim time if true'),
node_robot_state_publisher
])

View File

@@ -12,6 +12,7 @@
<depend>modelec_interface</depend>
<depend>rclcpp</depend>
<depend>std_msgs</depend>
<depend>sensor_msgs</depend>
<build_depend>boost</build_depend>
<exec_depend>boost</exec_depend>

View File

@@ -53,6 +53,8 @@ namespace Modelec {
[this](const std::vector<rclcpp::Parameter> &parameters) {
return onParameterChange(parameters);
});
clearAllDevices();
}
// Initialize PCA9685 in normal operation mode

View File

@@ -109,27 +109,22 @@ namespace Modelec {
// Reopen the connection with updated parameters
try {
if (port.is_open()) {
port.close(); // Close the current port before reopening
}
serialClose(fd);
if (!initializeConnection()) {
RCLCPP_ERROR(this->get_logger(), "Failed to reopen the serial port, shutting down.");
rclcpp::shutdown(); // Graceful shutdown if port opening fails
}
} catch (boost::system::system_error &e) {
RCLCPP_ERROR(this->get_logger(), "Error during connection update: %s", e.what());
rclcpp::shutdown();
} catch (std::exception &e) {
RCLCPP_ERROR(this->get_logger(), "Error updating connection parameters: %s", e.what());
}
}
void USBListener::write_to_arduino(const std::string &data) {
try {
boost::asio::write(port, boost::asio::buffer(data));
} catch (boost::system::system_error &e) {
RCLCPP_ERROR(this->get_logger(), "Error writing to serial port: %s", e.what());
}
serialPuts(fd, data.c_str());
serialFlush(fd);
RCLCPP_INFO(this->get_logger(), "Sent data: %s", data.c_str());
}
}

View File

@@ -0,0 +1,70 @@
<sdf version="1.6">
<world name="empty">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<plugin
filename="gz-sim-sensors-system"
name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin
filename="gz-sim-contact-system"
name="gz::sim::systems::Contact">
</plugin>
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>
</world>
</sdf>

View File

@@ -0,0 +1,935 @@
<sdf version='1.7'>
<world name='default'>
<light name='sun' type='directional'>
<cast_shadows>1</cast_shadows>
<pose>0 0 10 0 -0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
<spot>
<inner_angle>0</inner_angle>
<outer_angle>0</outer_angle>
<falloff>0</falloff>
</spot>
</light>
<model name='ground_plane'>
<static>1</static>
<link name='link'>
<collision name='collision'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<contact>
<collide_bitmask>65535</collide_bitmask>
<ode/>
</contact>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
<torsional>
<ode/>
</torsional>
</friction>
<bounce/>
</surface>
<max_contacts>10</max_contacts>
</collision>
<visual name='visual'>
<cast_shadows>0</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
</model>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type='adiabatic'/>
<physics type='ode'>
<max_step_size>0.001</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>
</physics>
<scene>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>1</shadows>
</scene>
<wind/>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<latitude_deg>0</latitude_deg>
<longitude_deg>0</longitude_deg>
<elevation>0</elevation>
<heading_deg>0</heading_deg>
</spherical_coordinates>
<model name='Construction Barrel'>
<link name='link'>
<inertial>
<pose>0 0 0.4 0 -0 0</pose>
<mass>500</mass>
<inertia>
<ixx>51.2096</ixx>
<iyy>51.2096</iyy>
<izz>25</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<collision name='collision'>
<geometry>
<mesh>
<uri>model://construction_barrel/meshes/construction_barrel.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<uri>model://construction_barrel/meshes/construction_barrel.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>-0.756237 1.39226 0 0 -0 0</pose>
</model>
<model name='Construction Barrel_0'>
<link name='link'>
<inertial>
<pose>0 0 0.4 0 -0 0</pose>
<mass>500</mass>
<inertia>
<ixx>51.2096</ixx>
<iyy>51.2096</iyy>
<izz>25</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<collision name='collision'>
<geometry>
<mesh>
<uri>model://construction_barrel/meshes/construction_barrel.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<uri>model://construction_barrel/meshes/construction_barrel.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>1.80022 0.377178 0 0 -0 0</pose>
</model>
<model name='Construction Cone'>
<link name='link'>
<collision name='collision'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>-2.19745 -2.25046 0 0 -0 0</pose>
</model>
<model name='Construction Cone_0'>
<link name='link'>
<collision name='collision'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>-1.40494 -2.55135 0 0 -0 0</pose>
</model>
<model name='Construction Cone_1'>
<link name='link'>
<collision name='collision'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>-0.501986 -2.9745 0 0 -0 0</pose>
</model>
<model name='Construction Cone_2'>
<link name='link'>
<collision name='collision'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>2.09724 -2.18232 0 0 -0 0</pose>
</model>
<model name='Construction Cone_3'>
<link name='link'>
<collision name='collision'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>-3.69879 0.345038 0 0 -0 0</pose>
</model>
<model name='Construction Cone_4'>
<link name='link'>
<collision name='collision'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>-0.406438 -4.23374 0 0 -0 0</pose>
</model>
<model name='Construction Cone_5'>
<link name='link'>
<collision name='collision'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>2.38815 -3.2576 0 0 -0 0</pose>
</model>
<model name='Construction Cone_6'>
<link name='link'>
<collision name='collision'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>2.39316 -4.49605 0 0 -0 0</pose>
</model>
<model name='Construction Cone_7'>
<link name='link'>
<collision name='collision'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>-3.00495 -2.78053 0 0 -0 0</pose>
</model>
<model name='Construction Cone_8'>
<link name='link'>
<collision name='collision'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>10 10 10</scale>
<uri>model://construction_cone/meshes/construction_cone.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>-4.64786 -0.646522 0 0 -0 0</pose>
</model>
<model name='Construction Barrel_1'>
<link name='link'>
<inertial>
<pose>0 0 0.4 0 -0 0</pose>
<mass>500</mass>
<inertia>
<ixx>51.2096</ixx>
<iyy>51.2096</iyy>
<izz>25</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<collision name='collision'>
<geometry>
<mesh>
<uri>model://construction_barrel/meshes/construction_barrel.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<uri>model://construction_barrel/meshes/construction_barrel.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>-5.3108 -2.23708 0 0 -0 0</pose>
</model>
<model name='Construction Barrel_2'>
<link name='link'>
<inertial>
<pose>0 0 0.4 0 -0 0</pose>
<mass>500</mass>
<inertia>
<ixx>51.2096</ixx>
<iyy>51.2096</iyy>
<izz>25</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<collision name='collision'>
<geometry>
<mesh>
<uri>model://construction_barrel/meshes/construction_barrel.dae</uri>
</mesh>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<uri>model://construction_barrel/meshes/construction_barrel.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose>-2.07692 -4.26198 0 0 -0 0</pose>
</model>
<state world_name='default'>
<sim_time>457 444000000</sim_time>
<real_time>459 829915274</real_time>
<wall_time>1646216792 728719362</wall_time>
<iterations>457444</iterations>
<model name='Construction Barrel'>
<pose>-0.756319 1.39223 0 0 0 -2.4e-05</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>-0.756319 1.39223 0 0 0 -2.4e-05</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>3.45865 5.7443 4.40608 1.34644 0.778762 3.14097</acceleration>
<wrench>1729.32 2872.15 2203.04 0 -0 0</wrench>
</link>
</model>
<model name='Construction Barrel_0'>
<pose>1.80014 0.377148 0 0 0 -2.2e-05</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>1.80014 0.377148 0 0 0 -2.2e-05</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>3.45864 5.7443 4.40608 1.34642 0.778778 3.14097</acceleration>
<wrench>1729.32 2872.15 2203.04 0 -0 0</wrench>
</link>
</model>
<model name='Construction Barrel_1'>
<pose>-5.31082 -2.23709 -0 0 -0 -7e-06</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>-5.31082 -2.23709 -0 0 -0 -7e-06</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>-3.87743 -2.8936 0.727843 -2.17783 0.268134 -3.13538</acceleration>
<wrench>-1938.71 -1446.8 363.922 0 -0 0</wrench>
</link>
</model>
<model name='Construction Barrel_2'>
<pose>-2.07693 -4.26199 -0 0 0 -4e-06</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>-2.07693 -4.26199 -0 0 0 -4e-06</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>7.60795 0.965639 1.20183 -2.41278 0.170207 0.001195</acceleration>
<wrench>3803.98 482.819 600.916 0 -0 0</wrench>
</link>
</model>
<model name='Construction Cone'>
<pose>-2.19745 -2.25046 -0 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>-2.19745 -2.25046 -0 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 -0 -0.008512 -2.58585 1.13682 3.14159</acceleration>
<wrench>0 -0 -0.008512 0 -0 0</wrench>
</link>
</model>
<model name='Construction Cone_0'>
<pose>-1.40494 -2.55135 -0 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>-1.40494 -2.55135 -0 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 -0 -0.008512 -2.58585 1.13682 3.14159</acceleration>
<wrench>0 -0 -0.008512 0 -0 0</wrench>
</link>
</model>
<model name='Construction Cone_1'>
<pose>-0.501986 -2.9745 -0 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>-0.501986 -2.9745 -0 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 -0 -0.008512 -2.58585 1.13682 3.14159</acceleration>
<wrench>0 -0 -0.008512 0 -0 0</wrench>
</link>
</model>
<model name='Construction Cone_2'>
<pose>2.09724 -2.18232 -0 1e-06 -0 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>2.09724 -2.18232 -0 1e-06 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>-0 -0 -9.79988 3e-05 2e-05 -0</acceleration>
<wrench>-0 -0 -9.79988 0 -0 0</wrench>
</link>
</model>
<model name='Construction Cone_3'>
<pose>-3.69879 0.345038 -1e-05 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>-3.69879 0.345038 -1e-05 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 0 -9.8 0 -0 0</acceleration>
<wrench>0 0 -9.8 0 -0 0</wrench>
</link>
</model>
<model name='Construction Cone_4'>
<pose>-0.406438 -4.23374 -0 0 -1e-06 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>-0.406438 -4.23374 -0 0 -1e-06 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>-0 0 0.008512 2.58585 -1.13682 -3.14159</acceleration>
<wrench>-0 0 0.008512 0 -0 0</wrench>
</link>
</model>
<model name='Construction Cone_5'>
<pose>2.38815 -3.2576 -0 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>2.38815 -3.2576 -0 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 -0 -0.008512 -2.58585 1.13682 3.14159</acceleration>
<wrench>0 -0 -0.008512 0 -0 0</wrench>
</link>
</model>
<model name='Construction Cone_6'>
<pose>2.39316 -4.49605 -0 0 -1e-06 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>2.39316 -4.49605 -0 0 -1e-06 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>-0 0 0.008512 2.58585 -1.13682 -3.14159</acceleration>
<wrench>-0 0 0.008512 0 -0 0</wrench>
</link>
</model>
<model name='Construction Cone_7'>
<pose>-3.00495 -2.78053 -0 0 -1e-06 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>-3.00495 -2.78053 -0 0 -1e-06 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>-0 0 0.008512 2.58585 -1.13682 -3.14159</acceleration>
<wrench>-0 0 0.008512 0 -0 0</wrench>
</link>
</model>
<model name='Construction Cone_8'>
<pose>-4.64786 -0.646522 -0 0 -1e-06 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>-4.64786 -0.646522 -0 0 -1e-06 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>-0 0 0.008512 2.58585 -1.13682 -3.14159</acceleration>
<wrench>-0 0 0.008512 0 -0 0</wrench>
</link>
</model>
<model name='ground_plane'>
<pose>0 0 0 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>0 0 0 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 0 0 0 -0 0</acceleration>
<wrench>0 0 0 0 -0 0</wrench>
</link>
</model>
<light name='sun'>
<pose>0 0 10 0 -0 0</pose>
</light>
</state>
<gui fullscreen='0'>
<camera name='user_camera'>
<pose>-15.5892 0.392985 21.6628 0 0.851642 0.028194</pose>
<view_controller>orbit</view_controller>
<projection_type>perspective</projection_type>
</camera>
</gui>
</world>
</sdf>