CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/autotest/blimp.py
Views: 1798
1
'''
2
Fly Blimp in SITL
3
4
AP_FLAKE8_CLEAN
5
'''
6
7
from __future__ import print_function
8
import os
9
import shutil
10
11
from pymavlink import mavutil
12
13
from vehicle_test_suite import TestSuite
14
15
# get location of scripts
16
testdir = os.path.dirname(os.path.realpath(__file__))
17
SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 584, 0)
18
19
# Flight mode switch positions are set-up in blimp.parm to be
20
# switch 1 = Land
21
# switch 2 = Manual
22
# switch 3 = Velocity
23
# switch 4 = Loiter
24
# switch 5 = Manual
25
# switch 6 = Manual
26
27
28
class AutoTestBlimp(TestSuite):
29
@staticmethod
30
def get_not_armable_mode_list():
31
return []
32
33
@staticmethod
34
def get_not_disarmed_settable_modes_list():
35
return []
36
37
@staticmethod
38
def get_no_position_not_settable_modes_list():
39
return []
40
41
@staticmethod
42
def get_position_armable_modes_list():
43
return []
44
45
@staticmethod
46
def get_normal_armable_modes_list():
47
return []
48
49
def log_name(self):
50
return "Blimp"
51
52
def default_mode(self):
53
return "MANUAL"
54
55
def test_filepath(self):
56
return os.path.realpath(__file__)
57
58
def default_speedup(self):
59
return 100
60
61
def set_current_test_name(self, name):
62
self.current_test_name_directory = "Blimp_Tests/" + name + "/"
63
64
def sitl_start_location(self):
65
return SITL_START_LOCATION
66
67
def sitl_streamrate(self):
68
return 5
69
70
def vehicleinfo_key(self):
71
return 'Blimp'
72
73
def default_frame(self):
74
return "Blimp"
75
76
def apply_defaultfile_parameters(self):
77
# Blimp passes in a defaults_filepath in place of applying
78
# parameters afterwards.
79
pass
80
81
def defaults_filepath(self):
82
return self.model_defaults_filepath(self.frame)
83
84
def wait_disarmed_default_wait_time(self):
85
return 120
86
87
def close(self):
88
super(AutoTestBlimp, self).close()
89
90
# [2014/05/07] FC Because I'm doing a cross machine build
91
# (source is on host, build is on guest VM) I cannot hard link
92
# This flag tells me that I need to copy the data out
93
if self.copy_tlog:
94
shutil.copy(self.logfile, self.buildlog)
95
96
def is_blimp(self):
97
return True
98
99
def get_stick_arming_channel(self):
100
return int(self.get_parameter("RCMAP_YAW"))
101
102
def get_disarm_delay(self):
103
return int(self.get_parameter("DISARM_DELAY"))
104
105
def set_autodisarm_delay(self, delay):
106
self.set_parameter("DISARM_DELAY", delay)
107
108
def FlyManual(self):
109
'''test manual mode'''
110
self.change_mode('MANUAL')
111
self.wait_ready_to_arm()
112
self.arm_vehicle()
113
114
acc = 0.5
115
116
# make sure we don't drift:
117
bl = self.mav.location()
118
tl = self.offset_location_ne(location=bl, metres_north=2, metres_east=0)
119
ttl = self.offset_location_ne(location=bl, metres_north=4, metres_east=0)
120
tr = self.offset_location_ne(location=bl, metres_north=4, metres_east=2)
121
ttr = self.offset_location_ne(location=bl, metres_north=4, metres_east=4)
122
123
if self.mavproxy is not None:
124
self.mavproxy.send(f"map icon {bl.lat} {bl.lng} flag\n")
125
self.mavproxy.send(f"map icon {tl.lat} {tl.lng} flag\n")
126
self.mavproxy.send(f"map icon {ttl.lat} {ttl.lng} flag\n")
127
self.mavproxy.send(f"map icon {tr.lat} {tr.lng} flag\n")
128
self.mavproxy.send(f"map icon {ttr.lat} {ttr.lng} flag\n")
129
130
self.set_rc(2, 2000)
131
self.wait_distance_to_location(tl, 0, acc, timeout=10)
132
self.set_rc(2, 1500)
133
self.wait_distance_to_location(ttl, 0, acc, timeout=15)
134
self.set_rc(1, 2000)
135
self.wait_distance_to_location(tr, 0, acc, timeout=10)
136
self.set_rc(1, 1500)
137
self.wait_distance_to_location(ttr, 0, acc, timeout=15)
138
self.change_mode('RTL')
139
self.wait_distance_to_location(bl, 0, 0.5, timeout=30, minimum_duration=5) # make sure it can hold position
140
self.change_mode('MANUAL')
141
142
self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot
143
144
self.set_rc(3, 2000)
145
self.wait_altitude(5, 5.5, relative=True, timeout=15)
146
self.set_rc(3, 1500)
147
148
self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot
149
150
self.set_rc(4, 1000)
151
self.wait_heading(340, accuracy=5, timeout=5) # short timeout to check yawrate
152
self.set_rc(4, 1500)
153
154
self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot
155
156
self.set_rc(3, 1000)
157
self.wait_altitude(0, 0.5, relative=True, timeout=20)
158
self.set_rc(3, 1500)
159
160
self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot
161
162
self.set_rc(4, 2000)
163
self.wait_heading(135, accuracy=5, timeout=10) # short timeout to check yawrate
164
self.set_rc(4, 1500)
165
166
self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot
167
168
self.disarm_vehicle()
169
170
def FlyLoiter(self):
171
'''test loiter mode'''
172
173
self.change_mode('LOITER')
174
self.wait_ready_to_arm()
175
self.arm_vehicle()
176
177
siz = 5
178
tim = 60
179
180
# make sure we don't drift:
181
bl = self.mav.location()
182
tl = self.offset_location_ne(location=bl, metres_north=siz, metres_east=0)
183
tr = self.offset_location_ne(location=bl, metres_north=siz, metres_east=siz)
184
br = self.offset_location_ne(location=bl, metres_north=0, metres_east=siz)
185
186
print("Locations are:")
187
print("bottom left ", bl.lat, bl.lng)
188
print("top left ", tl.lat, tl.lng)
189
print("top right ", tr.lat, tr.lng)
190
print("bottom right ", br.lat, br.lng)
191
192
if self.mavproxy is not None:
193
self.mavproxy.send(f"map icon {bl.lat} {bl.lng} flag\n")
194
self.mavproxy.send(f"map icon {tl.lat} {tl.lng} flag\n")
195
self.mavproxy.send(f"map icon {tr.lat} {tr.lng} flag\n")
196
self.mavproxy.send(f"map icon {br.lat} {br.lng} flag\n")
197
198
self.set_parameter("SIMPLE_MODE", 1)
199
200
self.set_rc(2, 2000)
201
self.wait_distance_to_location(tl, 0, 0.2, timeout=tim)
202
self.set_rc(2, 1500)
203
204
self.set_rc(1, 2000)
205
self.wait_distance_to_location(tr, 0, 0.5, timeout=tim)
206
self.set_rc(1, 1500)
207
208
self.set_rc(2, 1000)
209
self.wait_distance_to_location(br, 0, 0.5, timeout=tim)
210
self.set_rc(2, 1500)
211
212
self.set_rc(1, 1000)
213
self.wait_distance_to_location(bl, 0, 0.5, timeout=tim)
214
self.set_rc(1, 1500)
215
216
fin = self.mav.location()
217
218
self.set_rc(4, 1700)
219
self.wait_heading(135, accuracy=2, timeout=tim)
220
self.set_rc(4, 1500)
221
222
self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot
223
224
self.set_rc(3, 2000)
225
self.wait_altitude(5, 5.5, relative=True, timeout=60)
226
self.set_rc(3, 1000)
227
self.wait_altitude(0, 0.5, relative=True, timeout=60)
228
self.set_rc(3, 1500)
229
230
self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot
231
232
self.set_rc(4, 1300)
233
self.wait_heading(0, accuracy=2, timeout=tim)
234
self.set_rc(4, 1500)
235
236
self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot
237
238
self.disarm_vehicle()
239
240
def PREFLIGHT_Pressure(self):
241
'''test triggering pressure calibration with mavlink command'''
242
# as airspeed is not instantiated on Blimp we expect to
243
# instantly get back an accepted.
244
self.run_cmd(
245
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
246
p3=1, # p3, baro
247
)
248
249
def tests(self):
250
'''return list of all tests'''
251
# ret = super(AutoTestBlimp, self).tests()
252
ret = []
253
ret.extend([
254
self.FlyManual,
255
self.FlyLoiter,
256
self.PREFLIGHT_Pressure,
257
])
258
return ret
259
260
def disabled_tests(self):
261
return {
262
}
263
264