mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Tools: add arm and disarm tests
This commit is contained in:
parent
fa7ba7ddbc
commit
2f9f793ccf
@ -108,53 +108,7 @@ class AutoTestRover(AutoTest):
|
||||
# self.mav.wait_heartbeat()
|
||||
# self.arm_vehicle()
|
||||
#
|
||||
# # TEST ARM RADIO
|
||||
# def test_arm_motors_radio(self):
|
||||
# """Test Arming motors with radio."""
|
||||
# self.progress("Test arming motors with radio")
|
||||
# self.mavproxy.send('switch 6\n') # stabilize/manual mode
|
||||
# self.wait_mode('MANUAL')
|
||||
# self.mavproxy.send('rc 3 1500\n') # throttle at zero
|
||||
# self.mavproxy.send('rc 1 2000\n') # steer full right
|
||||
# self.mavproxy.expect('APM: Throttle armed')
|
||||
# self.mavproxy.send('rc 1 1500\n')
|
||||
#
|
||||
# self.mav.motors_armed_wait()
|
||||
# self.progress("MOTORS ARMED OK")
|
||||
# return True
|
||||
#
|
||||
# # TEST DISARM RADIO
|
||||
# def test_disarm_motors_radio(self):
|
||||
# """Test Disarm motors with radio."""
|
||||
# self.progress("Test disarming motors with radio")
|
||||
# self.mavproxy.send('switch 6\n') # stabilize/manual mode
|
||||
# self.wait_mode('MANUAL')
|
||||
# self.mavproxy.send('rc 3 1500\n') # throttle at zero
|
||||
# self.mavproxy.send('rc 1 1000\n') # steer full right
|
||||
# tstart = self.get_sim_time()
|
||||
# self.mav.wait_heartbeat()
|
||||
# timeout = 15
|
||||
# while self.get_sim_time() < tstart + timeout:
|
||||
# self.mav.wait_heartbeat()
|
||||
# if not self.mav.motors_armed():
|
||||
# disarm_delay = self.get_sim_time() - tstart
|
||||
# self.progress("MOTORS DISARMED OK WITH RADIO")
|
||||
# self.mavproxy.send('rc 1 1500\n') # steer full right
|
||||
# self.mavproxy.send('rc 4 1500\n') # yaw full right
|
||||
# self.progress("Disarm in %ss" % disarm_delay)
|
||||
# return True
|
||||
# self.progress("FAILED TO DISARM WITH RADIO")
|
||||
# return False
|
||||
#
|
||||
# # TEST AUTO DISARM
|
||||
# def test_autodisarm_motors(self):
|
||||
# """Test Autodisarm motors."""
|
||||
# self.progress("Test Autodisarming motors")
|
||||
# self.mavproxy.send('switch 6\n') # stabilize/manual mode
|
||||
# # NOT IMPLEMENTED ON ROVER
|
||||
# self.progress("MOTORS AUTODISARMED OK")
|
||||
# return True
|
||||
#
|
||||
|
||||
# # TEST RC OVERRIDE
|
||||
# # TEST RC OVERRIDE TIMEOUT
|
||||
# def test_rtl(self, home, distance_min=5, timeout=250):
|
||||
@ -598,6 +552,7 @@ class AutoTestRover(AutoTest):
|
||||
self.mavproxy.send('switch 6\n') # Manual mode
|
||||
self.wait_mode('MANUAL')
|
||||
self.wait_ready_to_arm()
|
||||
self.run_test("Arm features", self.test_arm_feature)
|
||||
self.arm_vehicle()
|
||||
|
||||
self.run_test("Set modes via mavproxy switch",
|
||||
|
@ -1662,7 +1662,8 @@ class AutoTestCopter(AutoTest):
|
||||
self.wait_mode('STABILIZE')
|
||||
|
||||
# Arm
|
||||
self.run_test("Arm motors", self.arm_vehicle)
|
||||
self.run_test("Arm features", self.test_arm_feature)
|
||||
self.arm_vehicle()
|
||||
|
||||
# Takeoff
|
||||
self.run_test("Takeoff to test fly Square",
|
||||
|
@ -568,6 +568,9 @@ class AutoTestPlane(AutoTest):
|
||||
self.mav.wait_gps_fix()
|
||||
self.homeloc = self.mav.location()
|
||||
self.progress("Home location: %s" % self.homeloc)
|
||||
self.wait_ready_to_arm()
|
||||
self.run_test("Arm features", self.test_arm_feature)
|
||||
self.arm_vehicle()
|
||||
|
||||
self.run_test("Flaps", self.fly_flaps)
|
||||
|
||||
|
@ -147,6 +147,8 @@ class AutoTestSub(AutoTest):
|
||||
# wait for EKF and GPS checks to pass
|
||||
self.progress("Waiting for ready-to-arm")
|
||||
self.wait_ready_to_arm()
|
||||
self.run_test("Arm features", self.test_arm_feature)
|
||||
self.arm_vehicle()
|
||||
|
||||
self.homeloc = self.mav.location()
|
||||
self.progress("Home location: %s" % self.homeloc)
|
||||
|
@ -397,6 +397,13 @@ class AutoTest(ABC):
|
||||
self.progress("Failed to send RC commands to channel %s" % str(chan))
|
||||
raise SetRCTimeout()
|
||||
|
||||
def set_throttle_zero(self):
|
||||
"""Set throttle to zero."""
|
||||
if self.mav.mav_type == mavutil.mavlink.MAV_TYPE_GROUND_ROVER:
|
||||
self.set_rc(3, 1500)
|
||||
else:
|
||||
self.set_rc(3, 1000)
|
||||
|
||||
def armed(self):
|
||||
'''Return true if vehicle is armed and safetyoff'''
|
||||
return self.mav.motors_armed()
|
||||
@ -415,6 +422,63 @@ class AutoTest(ABC):
|
||||
self.progress("DISARMED")
|
||||
return True
|
||||
|
||||
def arm_motors_with_rc_input(self):
|
||||
"""Arm motors with radio."""
|
||||
self.progress("Arm motors with radio")
|
||||
self.set_throttle_zero()
|
||||
self.mavproxy.send('rc 1 2000\n')
|
||||
tstart = self.get_sim_time()
|
||||
timeout = 15
|
||||
while self.get_sim_time() < tstart + timeout:
|
||||
self.mav.wait_heartbeat()
|
||||
if not self.mav.motors_armed():
|
||||
arm_delay = self.get_sim_time() - tstart
|
||||
self.progress("MOTORS ARMED OK WITH RADIO")
|
||||
self.mavproxy.send('rc 1 1500\n')
|
||||
self.progress("Arm in %ss" % arm_delay) # TODO check arming time
|
||||
return True
|
||||
self.progress("FAILED TO ARM WITH RADIO")
|
||||
self.mavproxy.send('rc 1 1500\n')
|
||||
return False
|
||||
|
||||
def disarm_motors_with_rc_input(self):
|
||||
"""Disarm motors with radio."""
|
||||
self.progress("Disarm motors with radio")
|
||||
self.set_throttle_zero()
|
||||
self.mavproxy.send('rc 1 1000\n')
|
||||
tstart = self.get_sim_time()
|
||||
timeout = 15
|
||||
while self.get_sim_time() < tstart + timeout:
|
||||
self.mav.wait_heartbeat()
|
||||
if not self.mav.motors_armed():
|
||||
disarm_delay = self.get_sim_time() - tstart
|
||||
self.progress("MOTORS DISARMED OK WITH RADIO")
|
||||
self.mavproxy.send('rc 1 1500\n')
|
||||
self.progress("Disarm in %ss" % disarm_delay) # TODO check disarming time
|
||||
return True
|
||||
self.progress("FAILED TO DISARM WITH RADIO")
|
||||
self.mavproxy.send('rc 1 1500\n')
|
||||
return False
|
||||
|
||||
def autodisarm_motors(self):
|
||||
"""Autodisarm motors."""
|
||||
self.progress("Autodisarming motors")
|
||||
self.set_throttle_zero()
|
||||
if self.mav.mav_type == mavutil.mavlink.MAV_TYPE_GROUND_ROVER: # NOT IMPLEMENTED ON ROVER
|
||||
self.progress("MOTORS AUTODISARMED OK")
|
||||
return True
|
||||
tstart = self.get_sim_time()
|
||||
timeout = 15
|
||||
while self.get_sim_time() < tstart + timeout:
|
||||
self.mav.wait_heartbeat()
|
||||
if not self.mav.motors_armed():
|
||||
disarm_delay = self.get_sim_time() - tstart
|
||||
self.progress("MOTORS AUTODISARMED")
|
||||
self.progress("Autodisarm in %ss" % disarm_delay) # TODO check disarming time
|
||||
return True
|
||||
self.progress("FAILED TO AUTODISARM")
|
||||
return False
|
||||
|
||||
def set_parameter(self, name, value, add_to_context=True):
|
||||
old_value = self.get_parameter(name)
|
||||
for i in range(1, 10):
|
||||
@ -907,26 +971,23 @@ class AutoTest(ABC):
|
||||
"""Initilialize autotest feature."""
|
||||
pass
|
||||
|
||||
# def test_common_feature(self):
|
||||
# """Common feature to test."""
|
||||
# sucess = True
|
||||
# # TEST ARMING/DISARM
|
||||
# if not self.arm_vehicle():
|
||||
# self.progress("Failed to ARM")
|
||||
# sucess = False
|
||||
# if not self.disarm_vehicle():
|
||||
# self.progress("Failed to DISARM")
|
||||
# sucess = False
|
||||
# if not self.test_arm_motors_radio():
|
||||
# self.progress("Failed to ARM with radio")
|
||||
# sucess = False
|
||||
# if not self.test_disarm_motors_radio():
|
||||
# self.progress("Failed to ARM with radio")
|
||||
# sucess = False
|
||||
# if not self.test_autodisarm_motors():
|
||||
# self.progress("Failed to AUTO DISARM")
|
||||
# sucess = False
|
||||
# # TODO: Test failure on arm (with arming check)
|
||||
def test_arm_feature(self):
|
||||
"""Common feature to test."""
|
||||
# TEST ARMING/DISARM
|
||||
if not self.arm_vehicle():
|
||||
self.progress("Failed to ARM")
|
||||
raise NotAchievedException()
|
||||
if not self.disarm_vehicle():
|
||||
self.progress("Failed to DISARM")
|
||||
raise NotAchievedException()
|
||||
if not self.arm_motors_with_rc_input():
|
||||
raise NotAchievedException()
|
||||
if not self.disarm_motors_with_rc_input():
|
||||
raise NotAchievedException()
|
||||
if not self.autodisarm_motors():
|
||||
raise NotAchievedException()
|
||||
# TODO : add failure test : arming check, wrong mode; Test arming magic; Same for disarm
|
||||
|
||||
# # TEST MISSION FILE
|
||||
# # TODO : rework that to work on autotest server
|
||||
# # self.progress("TEST LOADING MISSION")
|
||||
|
@ -152,6 +152,7 @@ class AutoTestQuadPlane(AutoTest):
|
||||
self.progress("Waiting reading for arm")
|
||||
self.wait_seconds(30)
|
||||
|
||||
self.run_test("Arm features", self.test_arm_feature)
|
||||
self.arm_vehicle()
|
||||
|
||||
m = os.path.join(testdir, "ArduPlane-Missions/Dalby-OBC2016.txt")
|
||||
|
Loading…
Reference in New Issue
Block a user