/
demo_2robots.world.xml
170 lines (145 loc) · 5.08 KB
/
demo_2robots.world.xml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
<mvsim_world version="1.0">
<!-- General simulation options -->
<simul_timestep>0</simul_timestep> <!-- Simulation fixed-time interval for numerical integration [seconds] or 0 to autodetermine -->
<!-- GUI options -->
<gui>
<ortho>false</ortho>
<show_forces>true</show_forces> <force_scale>0.01</force_scale>
<cam_distance>35</cam_distance>
<fov_deg>60</fov_deg>
<refresh_fps>20</refresh_fps>
<!-- <follow_vehicle>r1</follow_vehicle> -->
</gui>
<!-- Light parameters -->
<lights>
</lights>
<!-- ========================
Scenario definition
======================== -->
<!-- ground -->
<element class="horizontal_plane">
<cull_face>BACK</cull_face>
<x_min>-20</x_min>
<y_min>-20</y_min>
<x_max> 20</x_max>
<y_max> 20</y_max>
<z>0.0</z>
</element>
<!-- ground grid (for visual reference) -->
<element class="ground_grid">
<!--<floating>true</floating>-->
</element>
<!-- =============================
Vehicle classes definition
============================= -->
<include file="../definitions/ackermann.vehicle.xml" />
<include file="../definitions/small_robot.vehicle.xml" />
<!-- ========================
Vehicle(s) definition
======================== -->
<vehicle name="r1" class="small_robot">
<init_pose>17 0 90.0</init_pose> <!-- In global coords: x,y, yaw(deg) -->
<init_vel>0 0 0</init_vel> <!-- In local coords: vx,vy, omega(deg/s) -->
<publish>
<publish_pose_topic>/${NAME}/pose</publish_pose_topic>
<publish_pose_period>50e-3</publish_pose_period>
</publish>
<!-- Sensors -->
<include file="../definitions/lidar2d.sensor.xml"
sensor_x="0.5" sensor_y="0" sensor_z="0.70" sensor_yaw="0" sensor_name="laser1" raytrace_3d="true"
sensor_publish="true"
/>
<include file="../definitions/rgbd_camera.sensor.xml"
sensor_x="0.6" sensor_y="0" sensor_z="0.65"
/>
</vehicle>
<vehicle name="r2" class="car_ackermann">
<init_pose>-10.0 0 0</init_pose> <!-- In global coords: x,y, yaw(deg) -->
<init_vel>0 0 0</init_vel> <!-- In local coords: vx,vy, omega(deg/s) -->
<publish>
<publish_pose_topic>/${NAME}/pose</publish_pose_topic>
<publish_pose_period>50e-3</publish_pose_period>
</publish>
<!-- Sensors -->
<include file="../definitions/lidar2d.sensor.xml"
raytrace_3d="true" sensor_x="1.7" sensor_z="1.01" sensor_yaw="0" sensor_name="laser1"
sensor_publish="true"
/>
<!-- Sensors -->
<include file="../definitions/camera.sensor.xml"
sensor_x="1.9" sensor_z="0.5"
sensor_publish="true"
/>
</vehicle>
<!-- ======================================
Obstacle blocks classes definition
====================================== -->
<block:class name="square_obstacle">
<mass>20</mass>
<color>#0080ff</color>
<zmax>1.5</zmax>
<ground_friction>0.3</ground_friction>
<shape>
<pt>-1.0 -0.6</pt>
<pt>-1.0 0.6</pt>
<pt> 1.0 0.5</pt>
<pt> 1.0 -0.5</pt>
</shape>
</block:class>
<block:class name="nurse_station">
<mass>300</mass>
<color>#0080ff</color>
<ground_friction>100.0</ground_friction>
<shape_from_visual/> <!-- automatic shape,zmin,zmax from 3D mesh-->
<!-- Custom visualization model -->
<!-- 3D model filename to load (local or remote http://uri ) -->
<visual>
<model_uri>https://mrpt.github.io/mvsim-models/aws_robomaker_hospital_nursesstation_01.zip/aws_robomaker_hospital_nursesstation_01/aws_robomaker_hospital_nursesstation_01_visual.dae</model_uri>
</visual>
</block:class>
<!-- ========================
Obstacle blocks
======================== -->
<block class="square_obstacle">
<init_pose>6 5 0</init_pose> <!-- In global coords: x,y, yaw(deg) -->
<publish>
<publish_pose_topic>/${NAME}/pose</publish_pose_topic>
<publish_pose_period>50e-3</publish_pose_period>
</publish>
</block>
<!-- Example intangible block, used as a reference for relative pose sensing -->
<block name="blockSensor1">
<shape>
<pt>-0.05 -0.05</pt>
<pt>-0.05 0.05</pt>
<pt> 0.05 0.05</pt>
<pt> 0.05 -0.05</pt>
</shape>
<intangible>true</intangible>
<zmin>0.0</zmin>
<zmax>0.2</zmax>
<init_pose>2.5 -12 0</init_pose> <!-- In global coords: x,y, yaw(deg) -->
<publish>
<publish_pose_period>100e-3</publish_pose_period>
<!-- Comma separated list of objects, robots, etc. to sense and publish relative poses -->
<publish_relative_pose_objects>r1, r2</publish_relative_pose_objects>
<publish_relative_pose_topic>/relative_pose_readings</publish_relative_pose_topic>
</publish>
</block>
<!-- ========================================================
Standalone sensors (placed freely on the environment)
======================================================== -->
<sensor class="laser" name="proximitySensor1">
<pose>1.3 -18.3 90.0 </pose>
<fov_degrees>30</fov_degrees>
<nrays>5</nrays>
<range_std_noise>0.01</range_std_noise>
<angle_std_noise_deg>0.01</angle_std_noise_deg>
<publish>
<publish_topic>/${NAME}</publish_topic>
</publish>
</sensor>
<block class="nurse_station">
<init_pose>15 2 30</init_pose> <!-- In global coords: x,y, yaw(deg) -->
</block>
</mvsim_world>