Skip to content

Commit

Permalink
Merge pull request #67 from morpheus1820/madama_world
Browse files Browse the repository at this point in the history
Palazzo Madama gazebo world
  • Loading branch information
elandini84 authored Oct 16, 2024
2 parents 1ec3524 + f988ce1 commit d852afa
Show file tree
Hide file tree
Showing 6 changed files with 411 additions and 56 deletions.
167 changes: 167 additions & 0 deletions app/maps/SIM_MADAMA/madama.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,167 @@
<sdf version='1.7'>
<world name='default'>
<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/DarkGrey</name>
</script>
</material>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
</model>
<light name='sun1' 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='madama_walls'>
<pose>10 -11 0 0 0 1.561</pose>
<static>1</static>
<link name='body'>
<visual name='visual'>
<geometry>
<mesh>
<uri>palazzomadama.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='collision'>
<geometry>
<mesh>
<uri>palazzomadama.dae</uri>
</mesh>
</geometry>
<surface>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
<contact>
<ode/>
</contact>
<bounce/>
</surface>
<max_contacts>2</max_contacts>
</collision>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
</model>

<model name="SIM_CER_ROBOT">
<include>
<uri>model://cer_no_collisions_20m</uri>
</include>
</model>

<gravity>0 0 -9.81</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>
<state world_name='default'>

<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>
<model name='my_mesh'>
<pose>0 0 0 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='body'>
<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.017 7.47424 32.928 0 0.933798 3.03616</pose>
<view_controller>orbit</view_controller>
<projection_type>perspective</projection_type>
</camera>
</gui>
</world>
</sdf>
Loading

0 comments on commit d852afa

Please sign in to comment.