mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Tools: autotest: add PID_TUNING test
This commit is contained in:
parent
f33ba58549
commit
8c35ddc0eb
@ -870,6 +870,10 @@ class AutoTestPlane(AutoTest):
|
||||
def default_mode(self):
|
||||
return "MANUAL"
|
||||
|
||||
def test_pid_tuning(self):
|
||||
self.change_mode("FBWA") # we don't update PIDs in MANUAL
|
||||
super(AutoTestPlane, self).test_pid_tuning()
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = super(AutoTestPlane, self).tests()
|
||||
|
@ -2265,8 +2265,23 @@ switch value'''
|
||||
def disabled_tests(self):
|
||||
return {}
|
||||
|
||||
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=1)
|
||||
if m is not None:
|
||||
raise PreconditionFailedException("Receiving PID_TUNING already")
|
||||
self.set_parameter("GCS_PID_MASK", 1)
|
||||
self.progress("making sure we are now getting PID_TUNING messages")
|
||||
m = self.mav.recv_match(type='PID_TUNING', blocking=True, timeout=1)
|
||||
if m is None:
|
||||
raise PreconditionFailedException("Did not start to get PID_TUNING message")
|
||||
|
||||
def tests(self):
|
||||
return [
|
||||
("PIDTuning",
|
||||
"Test PID Tuning",
|
||||
self.test_pid_tuning),
|
||||
|
||||
("ArmFeatures", "Arm features", self.test_arm_feature),
|
||||
|
||||
("SetHome",
|
||||
|
@ -186,6 +186,10 @@ class AutoTestQuadPlane(AutoTest):
|
||||
return
|
||||
self.mav.motors_disarmed_wait()
|
||||
|
||||
def test_pid_tuning(self):
|
||||
self.change_mode("FBWA") # we don't update PIDs in MANUAL
|
||||
super(AutoTestQuadPlane, self).test_pid_tuning()
|
||||
|
||||
def default_mode(self):
|
||||
return "MANUAL"
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user