335 lines
8.4 KiB
Plaintext
335 lines
8.4 KiB
Plaintext
|
<?xml version="1.0" ?>
|
||
|
<sdf version="1.5">
|
||
|
<world name="default">
|
||
|
|
||
|
<!-- A global light source -->
|
||
|
<include>
|
||
|
<uri>model://sun</uri>
|
||
|
</include>
|
||
|
|
||
|
<!-- A ground plane -->
|
||
|
<include>
|
||
|
<uri>model://ground_plane</uri>
|
||
|
</include>
|
||
|
|
||
|
<!-- World plugin that publishes event messages.
|
||
|
The topics used in these messages match up with topics used by the
|
||
|
plugin in the elevator model below.
|
||
|
-->
|
||
|
<plugin filename="libSimEventsPlugin.so" name="elevator_event_plugin">
|
||
|
<!-- Region on the ground floor, in front of the elevator -->
|
||
|
<region>
|
||
|
<name>region1</name>
|
||
|
<volume>
|
||
|
<min>1.5 -1 0</min>
|
||
|
<max>2.5 1 1</max>
|
||
|
</volume>
|
||
|
</region>
|
||
|
|
||
|
<!-- Region on the first floor, in front of the elevator -->
|
||
|
<region>
|
||
|
<name>region2</name>
|
||
|
<volume>
|
||
|
<min>1.5 -1 3</min>
|
||
|
<max>2.5 1 4</max>
|
||
|
</volume>
|
||
|
</region>
|
||
|
|
||
|
<!-- Event publisher for ground floor-->
|
||
|
<event>
|
||
|
<name>region1_event</name>
|
||
|
<type>occupied</type>
|
||
|
<region>region1</region>
|
||
|
<topic>~/elevator</topic>
|
||
|
<msg_data>0</msg_data>
|
||
|
</event>
|
||
|
|
||
|
<!-- Event publisher for first floor-->
|
||
|
<event>
|
||
|
<name>region2_event</name>
|
||
|
<type>occupied</type>
|
||
|
<region>region2</region>
|
||
|
<topic>~/elevator</topic>
|
||
|
<msg_data>1</msg_data>
|
||
|
</event>
|
||
|
</plugin>
|
||
|
|
||
|
<!-- The elevator car -->
|
||
|
<model name="elevator">
|
||
|
<pose>0 0 0.075 0 0 0</pose>
|
||
|
<link name="link">
|
||
|
<inertial>
|
||
|
<mass>800</mass>
|
||
|
</inertial>
|
||
|
|
||
|
<collision name="floor_collision">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>2.25 2.25 0.15</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="floor_visual">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>2.25 2.25 0.15</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</visual>
|
||
|
|
||
|
<!-- wall1_collision is the wall to the right of the door, when
|
||
|
facing the door -->
|
||
|
<collision name="wall1_collision">
|
||
|
<pose>1.0745 0.5725 1.125 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.1 1.15 2.25</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="wall1_visual">
|
||
|
<pose>1.0745 0.5725 1.125 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.1 1.15 2.25</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>Gazebo/Red</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
|
||
|
<!-- wall2_collision is the wall to the left of the door, when
|
||
|
facing the door -->
|
||
|
<collision name="wall2_collision">
|
||
|
<pose>1.0745 -1.0625 1.125 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.1 0.125 2.25</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="wall2_visual">
|
||
|
<pose>1.0745 -1.0625 1.125 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.1 0.125 2.25</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>Gazebo/Red</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
</link>
|
||
|
|
||
|
<link name="door">
|
||
|
<pose>1.0745 -0.5 1.125 0 0 0</pose>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.08 1.0 2.25</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.08 1.0 2.25</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</visual>
|
||
|
</link>
|
||
|
|
||
|
<joint name="door" type="prismatic">
|
||
|
<parent>link</parent>
|
||
|
<child>door</child>
|
||
|
<axis>
|
||
|
<xyz>0 1 0</xyz>
|
||
|
<limit>
|
||
|
<lower>0</lower>
|
||
|
<upper>1</upper>
|
||
|
<effort>10</effort>
|
||
|
</limit>
|
||
|
|
||
|
<dynamics>
|
||
|
<damping>2</damping>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="lift" type="prismatic">
|
||
|
<parent>world</parent>
|
||
|
<child>link</child>
|
||
|
<axis>
|
||
|
<xyz>0 0 1</xyz>
|
||
|
<limit>
|
||
|
<lower>0</lower>
|
||
|
<upper>10</upper>
|
||
|
<effort>100000</effort>
|
||
|
</limit>
|
||
|
|
||
|
<dynamics>
|
||
|
<damping>50</damping>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<implicit_spring_damper>1</implicit_spring_damper>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
|
||
|
<!-- Plugin to control the elevator -->
|
||
|
<plugin filename="libElevatorPlugin.so" name="elevator_plugin">
|
||
|
<lift_joint>elevator::lift</lift_joint>
|
||
|
<door_joint>elevator::door</door_joint>
|
||
|
<floor_height>3.075</floor_height>
|
||
|
|
||
|
<!-- Time the elevator door will stay open in seconds -->
|
||
|
<door_wait_time>10</door_wait_time>
|
||
|
|
||
|
<!-- This topic is used to control the elevator -->
|
||
|
<topic>~/elevator</topic>
|
||
|
</plugin>
|
||
|
</model>
|
||
|
|
||
|
<!-- Elevator shaft -->
|
||
|
<model name="elevator_shaft">
|
||
|
<static>true</static>
|
||
|
<link name="link">
|
||
|
<collision name="shaft_wall1_collision">
|
||
|
<pose>0 1.25 3 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>2.5 0.15 6</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="shaft_wall1_visual">
|
||
|
<pose>0 1.25 3 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>2.5 0.15 6</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</visual>
|
||
|
|
||
|
<collision name="shaft_wall2_collision">
|
||
|
<pose>0 -1.25 3 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>2.5 0.15 6</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="shaft_wall2_visual">
|
||
|
<pose>0 -1.25 3 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>2.5 0.15 6</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</visual>
|
||
|
|
||
|
<collision name="shaft_wall3_collision">
|
||
|
<pose>-1.25 0 3 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.15 2.7 6</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="shaft_wall3_visual">
|
||
|
<pose>-1.25 0 3 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.15 2.7 6</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</visual>
|
||
|
|
||
|
<collision name="floor0_collision">
|
||
|
<pose>1.19 0 0.075 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.12 2.5 0.15</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="floor0_visual">
|
||
|
<pose>1.19 0 0.075 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.12 2.5 0.15</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</visual>
|
||
|
|
||
|
<collision name="floor1_collision">
|
||
|
<pose>1.19 0 3.075 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.12 2.5 0.15</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="floor1_visual">
|
||
|
<pose>1.19 0 3.075 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.12 2.5 0.15</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</visual>
|
||
|
</link>
|
||
|
</model>
|
||
|
|
||
|
<model name="floor0">
|
||
|
<pose>2.25 0 0.075 0 0 0</pose>
|
||
|
<static>true</static>
|
||
|
<link name="link">
|
||
|
<collision name="floor_collision">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>2.0 5.0 0.15</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="floor_visual">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>2.0 5.0 0.15</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</visual>
|
||
|
</link>
|
||
|
</model>
|
||
|
|
||
|
<model name="floor1">
|
||
|
<pose>2.25 0 3.075 0 0 0</pose>
|
||
|
<static>true</static>
|
||
|
<link name="link">
|
||
|
<collision name="floor_collision">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>2.0 5.0 0.15</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="floor_visual">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>2.0 5.0 0.15</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</visual>
|
||
|
</link>
|
||
|
</model>
|
||
|
|
||
|
</world>
|
||
|
</sdf>
|