mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
vehicle_test_suite: correct return value from armed()
this was returning the value of "128" rather than "True"
This commit is contained in:
parent
4933ef3f2d
commit
6dccdde660
@ -5412,9 +5412,9 @@ class TestSuite(ABC):
|
||||
)
|
||||
|
||||
def armed(self):
|
||||
"""Return true if vehicle is armed and safetyoff"""
|
||||
self.wait_heartbeat()
|
||||
return self.mav.motors_armed()
|
||||
"""Return True if vehicle is armed and safetyoff"""
|
||||
m = self.wait_heartbeat()
|
||||
return (m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED) != 0
|
||||
|
||||
def send_mavlink_arm_command(self):
|
||||
self.send_cmd(
|
||||
|
Loading…
Reference in New Issue
Block a user