-
Notifications
You must be signed in to change notification settings - Fork 2
/
iris_multiuav.world
150 lines (126 loc) · 3.75 KB
/
iris_multiuav.world
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
<?xml version="1.0" ?>
<!--
To run this demo, you must have following arducopter repo checked out:
https://github.com/iche033/ardupilot/tree/gazebo_sitl_irlock
Compile ArduCopter with SITL mode. Instructions are similar to:
http://ardupilot.org/dev/docs/building-px4-for-linux-with-make.html
but change the make target to sitl instead of px4-v2, i.e.
$ cd ardupilot/ArduCopter && make sitl
To start simulation, first run gazebo:
gazebo worlds/iris_irlock_demo.world
Gazebo starts up paused in a black screen. To run the simulation,
setup ArduCopter and run the command below in a separate terminal:
sim_vehicle.sh -j 4 -f Gazebo
This will start mavproxy. Wait until you have a GPS lock.
You can then do the usual mavprox commands with Gazebo, e.g.
# arm the motors
STABILIZE> arm throttle
# switch to LOITER mode
STABILIZE> mode LOITER
# take off using rc command
LOITER> rc 3 1700
# wait until the irlock beacon is within the view then switch to land mode
# to begin precision landing
LOITER> mode LAND
-->
<sdf version="1.6">
<world name="default">
<physics type="ode">
<ode>
<solver>
<type>quick</type>
<iters>100</iters>
<sor>1.0</sor>
</solver>
<constraints>
<cfm>0.0</cfm>
<erp>0.9</erp>
<contact_max_correcting_vel>0.1</contact_max_correcting_vel>
<contact_surface_layer>0.0</contact_surface_layer>
</constraints>
</ode>
<real_time_update_rate>0</real_time_update_rate>
<max_step_size>0.0025</max_step_size>
</physics>
<include>
<uri>model://sun</uri>
</include>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>5000 5000</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="runway">
<pose>000 0 0.005 0 0 -1.5707</pose>
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>1829 45</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Runway</name>
</script>
</material>
</visual>
<visual name="grass">
<pose>0 0 -0.1 0 0 0</pose>
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>5000 5000</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grass</name>
</script>
</material>
</visual>
</link>
</model>
<model name="iris_demo_1">
<pose> 0 0 0 0 0 0 0 </pose>
<include>
<uri>model://iris_with_standoffs_demo_1</uri>
</include>
</model>
<model name="iris_demo_2">
<pose> -10 -10 0 0 0 0 0 </pose>
<include>
<uri>model://iris_with_standoffs_demo_2</uri>
</include>
</model>
<model name="iris_demo_3">
<pose> -20 0 0 0 0 0 0 </pose>
<include>
<uri>model://iris_with_standoffs_demo_3</uri>
</include>
</model>
<model name="iris_demo_4">
<pose> -10 10 0 0 0 0 0 </pose>
<include>
<uri>model://iris_with_standoffs_demo_4</uri>
</include>
</model>
</world>
</sdf>