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