Tools: remove dependency on mavproxy for cmd_long based functions
This commit is contained in:
parent
87a7fd0fbb
commit
d8c53bbd9c
@ -747,6 +747,10 @@ class AutoTestRover(AutoTest):
|
|||||||
|
|
||||||
self.run_test("Set mode via MAV_COMMAND_DO_SET_MODE",
|
self.run_test("Set mode via MAV_COMMAND_DO_SET_MODE",
|
||||||
self.do_set_mode_via_command_long)
|
self.do_set_mode_via_command_long)
|
||||||
|
self.mavproxy.send('switch 6\n') # Manual mode
|
||||||
|
self.wait_mode('MANUAL')
|
||||||
|
self.run_test("Set mode via MAV_COMMAND_DO_SET_MODE with MAVProxy",
|
||||||
|
self.mavproxy_do_set_mode_via_command_long())
|
||||||
|
|
||||||
self.run_test("Test ServoRelayEvents",
|
self.run_test("Test ServoRelayEvents",
|
||||||
self.test_servorelayevents)
|
self.test_servorelayevents)
|
||||||
|
@ -673,20 +673,56 @@ class AutoTest(ABC):
|
|||||||
return bearing
|
return bearing
|
||||||
|
|
||||||
def do_get_autopilot_capabilities(self):
|
def do_get_autopilot_capabilities(self):
|
||||||
self.mavproxy.send("long REQUEST_AUTOPILOT_CAPABILITIES 1\n")
|
tstart = self.get_sim_time()
|
||||||
m = self.mav.recv_match(type='AUTOPILOT_VERSION',
|
while self.get_sim_time() - tstart < 10:
|
||||||
blocking=True,
|
# Cannot use run_cmd otherwise the respond is lost during the wait for ACK
|
||||||
timeout=10)
|
self.mav.mav.command_long_send(1,
|
||||||
if m is None:
|
1,
|
||||||
self.progress("AUTOPILOT_VERSION not received")
|
mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
|
||||||
raise NotAchievedException()
|
0, # confirmation
|
||||||
self.progress("AUTOPILOT_VERSION received")
|
1, # 1: Request autopilot version
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0)
|
||||||
|
m = self.mav.recv_match(type='AUTOPILOT_VERSION',
|
||||||
|
blocking=True,
|
||||||
|
timeout=10)
|
||||||
|
if m is not None:
|
||||||
|
self.progress("AUTOPILOT_VERSION received")
|
||||||
|
return
|
||||||
|
raise AutoTestTimeoutException()
|
||||||
|
|
||||||
def do_set_mode_via_command_long(self):
|
def do_set_mode_via_command_long(self):
|
||||||
base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
|
base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
|
||||||
custom_mode = 4 # hold
|
custom_mode = 4 # hold
|
||||||
start = time.time()
|
tstart = self.get_sim_time()
|
||||||
while time.time() - start < 5:
|
while self.get_sim_time() - tstart < 5:
|
||||||
|
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MODE,
|
||||||
|
base_mode,
|
||||||
|
custom_mode,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
)
|
||||||
|
m = self.mav.recv_match(type='HEARTBEAT',
|
||||||
|
blocking=True,
|
||||||
|
timeout=10)
|
||||||
|
if m is None:
|
||||||
|
raise ErrorException()
|
||||||
|
if m.custom_mode == custom_mode:
|
||||||
|
return
|
||||||
|
raise AutoTestTimeoutException()
|
||||||
|
|
||||||
|
def mavproxy_do_set_mode_via_command_long(self):
|
||||||
|
base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
|
||||||
|
custom_mode = 4 # hold
|
||||||
|
start = self.get_sim_time()
|
||||||
|
while self.get_sim_time() - start < 5:
|
||||||
self.mavproxy.send("long DO_SET_MODE %u %u\n" %
|
self.mavproxy.send("long DO_SET_MODE %u %u\n" %
|
||||||
(base_mode, custom_mode))
|
(base_mode, custom_mode))
|
||||||
m = self.mav.recv_match(type='HEARTBEAT',
|
m = self.mav.recv_match(type='HEARTBEAT',
|
||||||
@ -696,7 +732,6 @@ class AutoTest(ABC):
|
|||||||
raise ErrorException()
|
raise ErrorException()
|
||||||
if m.custom_mode == custom_mode:
|
if m.custom_mode == custom_mode:
|
||||||
return
|
return
|
||||||
time.sleep(0.1)
|
|
||||||
raise AutoTestTimeoutException()
|
raise AutoTestTimeoutException()
|
||||||
|
|
||||||
def reach_heading_manual(self, heading):
|
def reach_heading_manual(self, heading):
|
||||||
|
Loading…
Reference in New Issue
Block a user