|
|
|
@ -4181,10 +4181,7 @@ class AutoTest(ABC):
@@ -4181,10 +4181,7 @@ class AutoTest(ABC):
|
|
|
|
|
bearing += 360.00 |
|
|
|
|
return bearing |
|
|
|
|
|
|
|
|
|
def change_mode(self, mode, timeout=60): |
|
|
|
|
'''change vehicle flightmode''' |
|
|
|
|
self.wait_heartbeat() |
|
|
|
|
self.progress("Changing mode to %s" % mode) |
|
|
|
|
def send_cmd_do_set_mode(self, mode): |
|
|
|
|
self.send_cmd( |
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_SET_MODE, |
|
|
|
|
mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED, |
|
|
|
@ -4193,8 +4190,14 @@ class AutoTest(ABC):
@@ -4193,8 +4190,14 @@ class AutoTest(ABC):
|
|
|
|
|
0, |
|
|
|
|
0, |
|
|
|
|
0, |
|
|
|
|
0, |
|
|
|
|
0 |
|
|
|
|
) |
|
|
|
|
|
|
|
|
|
def change_mode(self, mode, timeout=60): |
|
|
|
|
'''change vehicle flightmode''' |
|
|
|
|
self.wait_heartbeat() |
|
|
|
|
self.progress("Changing mode to %s" % mode) |
|
|
|
|
self.send_cmd_do_set_mode(mode) |
|
|
|
|
tstart = self.get_sim_time() |
|
|
|
|
while not self.mode_is(mode): |
|
|
|
|
custom_num = self.mav.messages['HEARTBEAT'].custom_mode |
|
|
|
@ -4203,7 +4206,7 @@ class AutoTest(ABC):
@@ -4203,7 +4206,7 @@ class AutoTest(ABC):
|
|
|
|
|
if (timeout is not None and |
|
|
|
|
self.get_sim_time_cached() > tstart + timeout): |
|
|
|
|
raise WaitModeTimeout("Did not change mode") |
|
|
|
|
self.mavproxy.send('mode %s\n' % mode) |
|
|
|
|
self.send_cmd_do_set_mode(mode) |
|
|
|
|
self.progress("Got mode %s" % mode) |
|
|
|
|
|
|
|
|
|
def capable(self, capability): |
|
|
|
|