-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathiris_ardupilot.world
228 lines (198 loc) · 5.47 KB
/
iris_ardupilot.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
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
<?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.14500 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.15 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">
<pose> -8 0 0 0 0 0 </pose>
<include>
<uri>model://iris_with_standoffs_demo</uri>
<pose> 0 0 0 0 0 0 </pose>
</include>
</model>
<!--<model name="red_trial">
<pose> 0 0 0 0 0 0 </pose>
<link name='black_sheet'>
<inertial>
<mass>0.2</mass>
</inertial>
<collision name='black_sheet_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>1.5 1.5 .05</size>
</box>
</geometry>
</collision>
<visual name='black_sheet_visual'>
<material>
<script>
<name>Gazebo/Black</name>
<uri>__default__</uri>
</script>
</material>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>1.5 1.5 .05</size>
</box>
</geometry>
</visual>
</link>
<link name='red_sheet'>
<inertial>
<mass>0.05</mass>
</inertial>
<collision name='red_sheet_collision'>
<pose>0 0 0.05 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.25</radius>
<length>0.001</length>
</cylinder>
</geometry>
</collision>
<visual name='red_sheet_visual'>
<material>
<ambient>1 0 0 0.2</ambient>
<diffuse>1 0.1 0.2 1</diffuse>
<specular>0 0 0 0</specular>
<emissive>0 0 0 1</emissive>
</material>
<pose>0 0 0.05 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.25</radius>
<length>0.001</length>
</cylinder>
</geometry>
</visual>
</link>
<joint name='red_sheet_joint' type='fixed'>
<parent>black_sheet</parent>
<child>red_sheet</child>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
</model>-->
<model name="rover_ardupilot">
<pose>0 0 0 0 0 0 </pose>
<include>
<uri>model://rover_ardupilot</uri>
<pose>0 0 0 0 0 0</pose>
</include>
</model>
<!--<population name="population">
<model name="shelf">
<include>
<static>true</static>
<uri>model://bookshelf</uri>
</include>
</model>
<pose>0 0 0 0 0 0</pose>
<box>
<size>20 20 10</size>
</box>
<model_count>10</model_count>
<distribution>
<type>random</type>
</distribution>
</population>-->
</world>
</sdf>