mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Tools: autotest: add test for QuadPlane controller pre-arm checks
This commit is contained in:
parent
cf45b54070
commit
b47b97a981
@ -2786,31 +2786,7 @@ class AutoTestCopter(AutoTest):
|
||||
super(AutoTestCopter, self).test_arm_feature()
|
||||
|
||||
def test_parameter_checks(self):
|
||||
self.wait_ready_to_arm()
|
||||
self.context_push()
|
||||
self.set_parameter("PSC_POSXY_P", -1)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=2,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
|
||||
self.context_pop()
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=2,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED)
|
||||
self.disarm_vehicle()
|
||||
self.test_parameter_checks_poscontrol("PSC")
|
||||
|
||||
def initial_mode(self):
|
||||
return "STABILIZE"
|
||||
|
@ -2330,6 +2330,33 @@ switch value'''
|
||||
def disabled_tests(self):
|
||||
return {}
|
||||
|
||||
def test_parameter_checks_poscontrol(self, param_prefix):
|
||||
self.wait_ready_to_arm()
|
||||
self.context_push()
|
||||
self.set_parameter("%s_POSXY_P" % param_prefix, -1)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=2,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
|
||||
self.context_pop()
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=2,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED)
|
||||
self.disarm_vehicle()
|
||||
|
||||
def test_pid_tuning(self):
|
||||
self.progress("making sure we're not getting PID_TUNING messages")
|
||||
m = self.mav.recv_match(type='PID_TUNING', blocking=True, timeout=5)
|
||||
|
@ -192,6 +192,9 @@ class AutoTestQuadPlane(AutoTest):
|
||||
self.change_mode("FBWA") # we don't update PIDs in MANUAL
|
||||
super(AutoTestQuadPlane, self).test_pid_tuning()
|
||||
|
||||
def test_parameter_checks(self):
|
||||
self.test_parameter_checks_poscontrol("Q_P")
|
||||
|
||||
def default_mode(self):
|
||||
return "MANUAL"
|
||||
|
||||
@ -212,6 +215,10 @@ class AutoTestQuadPlane(AutoTest):
|
||||
|
||||
("QAutoTune", "Fly QAUTOTUNE mode", self.fly_qautotune),
|
||||
|
||||
("ParameterChecks",
|
||||
"Test Arming Parameter Checks",
|
||||
self.test_parameter_checks),
|
||||
|
||||
("Mission", "Dalby Mission",
|
||||
lambda: self.fly_mission(m, f))
|
||||
])
|
||||
|
Loading…
Reference in New Issue
Block a user