qt_pi/gazebo_sim/worlds/qt_pi_laser.world

2061 lines
60 KiB
Plaintext

<sdf version='1.6'>
<world name='default'>
<light name='sun' type='directional'>
<cast_shadows>1</cast_shadows>
<pose frame=''>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>1</static>
<link name='link'>
<collision name='collision'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
<torsional>
<ode/>
</torsional>
</friction>
<contact>
<ode/>
</contact>
<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 name='default_physics' default='0' 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='playground'>
<pose frame=''>-1.25415 -0.788564 0 0 -0 0</pose>
<link name='Wall_10'>
<collision name='Wall_10_Collision'>
<geometry>
<box>
<size>26.75 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_10_Visual'>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>26.75 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<pose frame=''>0.007886 -3.91706 0 0 -0 0</pose>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_11'>
<collision name='Wall_11_Collision'>
<geometry>
<box>
<size>8 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_11_Visual'>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>8 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<pose frame=''>13.3079 0.007941 0 0 -0 1.5708</pose>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_12'>
<collision name='Wall_12_Collision'>
<geometry>
<box>
<size>26.75 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_12_Visual'>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>26.75 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<pose frame=''>0.007886 3.93294 0 0 -0 3.14159</pose>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_21'>
<pose frame=''>-9.18476 0.019386 0 0 0 -1.5708</pose>
<visual name='Wall_21_Visual_0'>
<pose frame=''>-3.12221 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>1.75558 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_21_Collision_0'>
<geometry>
<box>
<size>1.75558 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>-3.12221 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_21_Visual_1'>
<pose frame=''>0.438191 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>3.56521 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_21_Collision_1'>
<geometry>
<box>
<size>3.56521 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>0.438191 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_21_Visual_2'>
<pose frame=''>3.5604 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>0.879203 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_21_Collision_2'>
<geometry>
<box>
<size>0.879203 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>3.5604 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_21_Visual_3'>
<pose frame=''>-1.79442 0 2.25 0 -0 0</pose>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_21_Collision_3'>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<pose frame=''>-1.79442 0 2.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_21_Visual_4'>
<pose frame=''>2.6708 0 2.25 0 -0 0</pose>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_21_Collision_4'>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<pose frame=''>2.6708 0 2.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_23'>
<collision name='Wall_23_Collision'>
<geometry>
<box>
<size>4.25 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_23_Visual'>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>4.25 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<pose frame=''>-11.2579 -1.35252 0 0 -0 3.14159</pose>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_25'>
<pose frame=''>-6.89009 -0.019386 0 0 0 -1.5708</pose>
<visual name='Wall_25_Visual_0'>
<pose frame=''>-2.05546 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>3.88908 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_25_Collision_0'>
<geometry>
<box>
<size>3.88908 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>-2.05546 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_25_Visual_1'>
<pose frame=''>2.39454 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>3.21092 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_25_Collision_1'>
<geometry>
<box>
<size>3.21092 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>2.39454 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_25_Visual_2'>
<pose frame=''>0.339077 0 2.25 0 -0 0</pose>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_25_Collision_2'>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<pose frame=''>0.339077 0 2.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_27'>
<pose frame=''>-2.84009 1.17017 0 0 -0 0</pose>
<visual name='Wall_27_Visual_0'>
<pose frame=''>-2.27097 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>3.70805 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_27_Collision_0'>
<geometry>
<box>
<size>3.70805 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>-2.27097 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_27_Visual_1'>
<pose frame=''>2.30403 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>3.64195 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_27_Collision_1'>
<geometry>
<box>
<size>3.64195 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>2.30403 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_27_Visual_2'>
<pose frame=''>0.033055 0 2.25 0 -0 0</pose>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_27_Collision_2'>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<pose frame=''>0.033055 0 2.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_33'>
<pose frame=''>1.21568 0.006434 0 0 -0 1.5708</pose>
<visual name='Wall_33_Visual_0'>
<pose frame=''>-2.30688 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>3.38624 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_33_Collision_0'>
<geometry>
<box>
<size>3.38624 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>-2.30688 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_33_Visual_1'>
<pose frame=''>2.14312 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>3.71376 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_33_Collision_1'>
<geometry>
<box>
<size>3.71376 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>2.14312 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_33_Visual_2'>
<pose frame=''>-0.163762 0 2.25 0 -0 0</pose>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_33_Collision_2'>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<pose frame=''>-0.163762 0 2.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_35'>
<collision name='Wall_35_Collision'>
<geometry>
<box>
<size>5 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_35_Visual'>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>5 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<pose frame=''>3.62057 -1.58539 0 0 -0 0</pose>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_36'>
<pose frame=''>6.04557 -2.76039 0 0 0 -1.5708</pose>
<visual name='Wall_36_Visual_0'>
<pose frame=''>-0.84415 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>0.811701 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_36_Collision_0'>
<geometry>
<box>
<size>0.811701 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>-0.84415 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_36_Visual_1'>
<pose frame=''>0.85585 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>0.788299 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_36_Collision_1'>
<geometry>
<box>
<size>0.788299 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>0.85585 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_36_Visual_2'>
<pose frame=''>0.011701 0 2.25 0 -0 0</pose>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_36_Collision_2'>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<pose frame=''>0.011701 0 2.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_38'>
<pose frame=''>3.40806 1.10972 0 0 -0 1.5708</pose>
<visual name='Wall_38_Visual_0'>
<pose frame=''>-2.20336 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>1.09329 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_38_Collision_0'>
<geometry>
<box>
<size>1.09329 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>-2.20336 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_38_Visual_1'>
<pose frame=''>0.181127 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>1.87567 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_38_Collision_1'>
<geometry>
<box>
<size>1.87567 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>0.181127 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_38_Visual_2'>
<pose frame=''>2.38448 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>0.731036 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_38_Collision_2'>
<geometry>
<box>
<size>0.731036 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>2.38448 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_38_Visual_3'>
<pose frame=''>-1.20671 0 2.25 0 -0 0</pose>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_38_Collision_3'>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<pose frame=''>-1.20671 0 2.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_38_Visual_4'>
<pose frame=''>1.56896 0 2.25 0 -0 0</pose>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_38_Collision_4'>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<pose frame=''>1.56896 0 2.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_40'>
<collision name='Wall_40_Collision'>
<geometry>
<box>
<size>4.5 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_40_Visual'>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>4.5 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<pose frame=''>5.60318 1.67301 0 0 -0 0</pose>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_41'>
<pose frame=''>7.77818 2.72301 0 0 -0 1.5708</pose>
<visual name='Wall_41_Visual_0'>
<pose frame=''>-0.729206 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>0.791587 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_41_Collision_0'>
<geometry>
<box>
<size>0.791587 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>-0.729206 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_41_Visual_1'>
<pose frame=''>0.845794 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>0.558413 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_41_Collision_1'>
<geometry>
<box>
<size>0.558413 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>0.845794 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_41_Visual_2'>
<pose frame=''>0.116587 0 2.25 0 -0 0</pose>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_41_Collision_2'>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<pose frame=''>0.116587 0 2.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_43'>
<pose frame=''>10.5278 0.085507 0 0 0 -0.523599</pose>
<visual name='Wall_43_Visual_0'>
<pose frame=''>-0.945166 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>4.60967 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_43_Collision_0'>
<geometry>
<box>
<size>4.60967 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>-0.945166 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_43_Visual_1'>
<pose frame=''>2.75483 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>0.990333 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_43_Collision_1'>
<geometry>
<box>
<size>0.990333 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>2.75483 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_43_Visual_2'>
<pose frame=''>1.80967 0 2.25 0 -0 0</pose>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_43_Collision_2'>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<pose frame=''>1.80967 0 2.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_45'>
<pose frame=''>10.3472 -1.82517 0 0 0 -1.5708</pose>
<visual name='Wall_45_Visual_0'>
<pose frame=''>-0.985004 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>2.27999 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_45_Collision_0'>
<geometry>
<box>
<size>2.27999 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>-0.985004 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_45_Visual_1'>
<pose frame=''>1.59 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>1.07001 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_45_Collision_1'>
<geometry>
<box>
<size>1.07001 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>1.59 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_45_Visual_2'>
<pose frame=''>0.604992 0 2.25 0 -0 0</pose>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<collision name='Wall_45_Collision_2'>
<geometry>
<box>
<size>0.9 0.15 0.5</size>
</box>
</geometry>
<pose frame=''>0.604992 0 2.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='Wall_9'>
<collision name='Wall_9_Collision'>
<geometry>
<box>
<size>8 0.15 2.5</size>
</box>
</geometry>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_9_Visual'>
<pose frame=''>0 0 1.25 0 -0 0</pose>
<geometry>
<box>
<size>8 0.15 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<ambient>1 1 1 1</ambient>
</material>
</visual>
<pose frame=''>-13.2921 0.007941 0 0 0 -1.5708</pose>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<static>1</static>
</model>
<model name='qt_pi_laser'>
<link name='chassis'>
<pose frame=''>0 0 0.1 0 -0 0</pose>
<inertial>
<mass>20</mass>
<pose frame=''>0.1 0 -0.05 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
<collision name='collision'>
<geometry>
<box>
<size>0.4 0.2 0.1</size>
</box>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>0.4 0.2 0.1</size>
</box>
</geometry>
</visual>
<collision name='caster_collision'>
<pose frame=''>0.15 0 -0.05 0 -0 0</pose>
<geometry>
<sphere>
<radius>0.05</radius>
</sphere>
</geometry>
<surface>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0.01</threshold>
</bounce>
<contact>
<ode>
<max_vel>0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1</slip1>
<slip2>1</slip2>
</ode>
<torsional>
<ode/>
</torsional>
</friction>
</surface>
<max_contacts>10</max_contacts>
</collision>
<visual name='caster_visual'>
<pose frame=''>0.15 0 -0.05 0 -0 0</pose>
<geometry>
<sphere>
<radius>0.05</radius>
</sphere>
</geometry>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='left_wheel'>
<pose frame=''>-0.1 0.2 0.1 0 -0 0</pose>
<inertial>
<mass>5</mass>
<pose frame=''>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>
</inertial>
<collision name='collision'>
<surface>
<friction>
<ode>
<mu>10</mu>
<mu2>10</mu2>
</ode>
<torsional>
<ode/>
</torsional>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0.01</threshold>
</bounce>
<contact>
<ode>
<max_vel>0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<max_contacts>10</max_contacts>
</collision>
<visual name='visual'>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<link name='right_wheel'>
<pose frame=''>-0.1 -0.2 0.1 0 -0 0</pose>
<inertial>
<mass>5</mass>
<pose frame=''>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>
</inertial>
<collision name='collision'>
<surface>
<friction>
<ode>
<mu>10</mu>
<mu2>10</mu2>
</ode>
<torsional>
<ode/>
</torsional>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0.01</threshold>
</bounce>
<contact>
<ode>
<max_vel>0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<max_contacts>10</max_contacts>
</collision>
<visual name='visual'>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<joint name='left_wheel_hinge' type='revolute'>
<pose frame=''>0 0 0 0 -0 0</pose>
<child>left_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>0</use_parent_model_frame>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<joint name='right_wheel_hinge' type='revolute'>
<pose frame=''>0 0 0 0 -0 0</pose>
<child>right_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>0</use_parent_model_frame>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='hokuyo::link'>
<inertial>
<mass>0.1</mass>
<pose frame=''>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>
</inertial>
<visual name='visual'>
<geometry>
<mesh>
<uri>model://hokuyo/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='collision-base'>
<pose frame=''>0 0 -0.0145 0 -0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.041</size>
</box>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<collision name='collision-top'>
<pose frame=''>0 0 0.0205 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.021</radius>
<length>0.029</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<sensor name='laser' type='ray'>
<pose frame=''>0.01 0 0.0175 0 -0 0</pose>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-2.26889</min_angle>
<max_angle>2.2689</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</vertical>
</scan>
<range>
<min>0.08</min>
<max>10</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name='laser' filename='libgazebo_ros_laser.so'>
<topicName>scan</topicName>
<frameName>laser</frameName>
<always_on>1</always_on>
<robotNamespace>qt_pi</robotNamespace>
<update_rate>15</update_rate>
</plugin>
<update_rate>15</update_rate>
<visualize>1</visualize>
</sensor>
<pose frame=''>0.2 0 0.2 0 -0 0</pose>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<joint name='hokuyo_joint' type='fixed'>
<child>hokuyo::link</child>
<parent>chassis</parent>
</joint>
<plugin name='differential_drive_controller' filename='libgazebo_ros_diff_drive.so'>
<alwaysOn>1</alwaysOn>
<updateRate>30</updateRate>
<leftJoint>left_wheel_hinge</leftJoint>
<robotNamespace>qt_pi</robotNamespace>
<rightJoint>right_wheel_hinge</rightJoint>
<wheelSeparation>0.4</wheelSeparation>
<wheelDiameter>0.2</wheelDiameter>
<publishWheelTF>0</publishWheelTF>
<wheelTorque>5</wheelTorque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<robotBaseFrame>base_link</robotBaseFrame>
<odometryFrame>odom</odometryFrame>
<publishTf>1</publishTf>
<publishOdomTF>1</publishOdomTF>
<rosDebugLevel>1</rosDebugLevel>
<publishWheelJointState>0</publishWheelJointState>
<wheelAcceleration>0</wheelAcceleration>
</plugin>
<pose frame=''>-0.306574 -6.64995 0 0 -0 0</pose>
</model>
<state world_name='default'>
<sim_time>65 341000000</sim_time>
<real_time>65 969333035</real_time>
<wall_time>1554402610 693687615</wall_time>
<iterations>65341</iterations>
<model name='ground_plane'>
<pose frame=''>0 0 0 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose frame=''>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>
<model name='playground'>
<pose frame=''>0 0 0 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='Wall_10'>
<pose frame=''>0.007886 -3.91706 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>
<link name='Wall_11'>
<pose frame=''>13.3079 0.007941 0 0 -0 1.5708</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>
<link name='Wall_12'>
<pose frame=''>0.007886 3.93294 0 0 -0 3.14159</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>
<link name='Wall_21'>
<pose frame=''>-9.18476 0.019386 0 0 0 -1.5708</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>
<link name='Wall_23'>
<pose frame=''>-11.2579 -1.35252 0 0 -0 3.14159</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>
<link name='Wall_25'>
<pose frame=''>-6.89009 -0.019386 0 0 0 -1.5708</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>
<link name='Wall_27'>
<pose frame=''>-2.84009 1.17017 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>
<link name='Wall_33'>
<pose frame=''>1.21568 0.006434 0 0 -0 1.5708</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>
<link name='Wall_35'>
<pose frame=''>3.62057 -1.58539 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>
<link name='Wall_36'>
<pose frame=''>6.04557 -2.76039 0 0 0 -1.5708</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>
<link name='Wall_38'>
<pose frame=''>3.40806 1.10972 0 0 -0 1.5708</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>
<link name='Wall_40'>
<pose frame=''>5.60318 1.67301 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>
<link name='Wall_41'>
<pose frame=''>7.77818 2.72301 0 0 -0 1.5708</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>
<link name='Wall_43'>
<pose frame=''>10.5278 0.085507 0 0 0 -0.523599</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>
<link name='Wall_45'>
<pose frame=''>10.3472 -1.82517 0 0 0 -1.5708</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>
<link name='Wall_9'>
<pose frame=''>-13.2921 0.007941 0 0 0 -1.5708</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>
<model name='qt_pi_laser'>
<pose frame=''>-0 0 0 0 0 0</pose>
<scale>1 1 1</scale>
<link name='chassis'>
<pose frame=''>0 0 0.1 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>
<link name='hokuyo::link'>
<pose frame=''>0.2 0 0.2 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>
<link name='left_wheel'>
<pose frame=''>-0.1 0.2 0.1 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>
<link name='right_wheel'>
<pose frame=''>-0.1 -0.2 0.1 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 frame=''>0 0 10 0 -0 0</pose>
</light>
</state>
<gui fullscreen='0'>
<camera name='user_camera'>
<pose frame=''>-4.72192 -0.583216 33.7134 -0 1.5418 0.060154</pose>
<view_controller>orbit</view_controller>
<projection_type>perspective</projection_type>
</camera>
</gui>
</world>
</sdf>