|
|
|
@ -2738,6 +2738,26 @@ class AutoTestPlane(AutoTest):
@@ -2738,6 +2738,26 @@ class AutoTestPlane(AutoTest):
|
|
|
|
|
attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=6) |
|
|
|
|
attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=7) |
|
|
|
|
|
|
|
|
|
def run_auxfunc(self, function, level): |
|
|
|
|
self.run_cmd( |
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_AUX_FUNCTION, |
|
|
|
|
function, # p1 |
|
|
|
|
level, # p2 |
|
|
|
|
0, # p3 |
|
|
|
|
0, # p4 |
|
|
|
|
0, # p5 |
|
|
|
|
0, # p6 |
|
|
|
|
0, # p7 |
|
|
|
|
) |
|
|
|
|
|
|
|
|
|
def fly_aux_function(self): |
|
|
|
|
self.context_collect('STATUSTEXT') |
|
|
|
|
self.run_auxfunc(64, 2) # 64 == reverse throttle |
|
|
|
|
self.wait_statustext("RevThrottle: ENABLE", check_context=True) |
|
|
|
|
self.run_auxfunc(64, 0) |
|
|
|
|
self.wait_statustext("RevThrottle: DISABLE", check_context=True) |
|
|
|
|
self.run_auxfunc(65, 2) # 65 == GPS_DISABLE |
|
|
|
|
|
|
|
|
|
def tests(self): |
|
|
|
|
'''return list of all tests''' |
|
|
|
|
ret = super(AutoTestPlane, self).tests() |
|
|
|
@ -2911,6 +2931,10 @@ class AutoTestPlane(AutoTest):
@@ -2911,6 +2931,10 @@ class AutoTestPlane(AutoTest):
|
|
|
|
|
"Test IMU temperature calibration", |
|
|
|
|
self.test_imu_tempcal), |
|
|
|
|
|
|
|
|
|
("MAV_DO_AUX_FUNCTION", |
|
|
|
|
"Test triggering Auxillary Functions via mavlink", |
|
|
|
|
self.fly_aux_function), |
|
|
|
|
|
|
|
|
|
("LogUpload", |
|
|
|
|
"Log upload", |
|
|
|
|
self.log_upload), |
|
|
|
|