/
demo_camera.world.xml
97 lines (83 loc) · 2.84 KB
/
demo_camera.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
<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>
<!-- ========================
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>
<!-- =============================
Vehicle classes definition
============================= -->
<include file="../definitions/small_robot.vehicle.xml" />
<!-- ========================
Vehicle(s) definition
======================== -->
<vehicle name="r1" class="small_robot">
<init_pose>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/camera.sensor.xml"
sensor_x="0.6" sensor_y="0" sensor_z="0.65"
sensor_period_sec="0.10"
/>
</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">
<static>true</static> <!-- Does not move -->
<color>#0080ff</color>
<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>
<block class="nurse_station">
<init_pose>10 0 -90</init_pose> <!-- In global coords: x,y, yaw(deg) -->
</block>
</mvsim_world>