Tools: autotest: add test for Copter PID parameter checks
This commit is contained in:
parent
a2ebdf6f2e
commit
b40f03dfbe
@ -2750,6 +2750,33 @@ 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()
|
||||
|
||||
def initial_mode(self):
|
||||
return "STABILIZE"
|
||||
|
||||
@ -2905,6 +2932,10 @@ class AutoTestCopter(AutoTest):
|
||||
"Test Parachute Functionality",
|
||||
self.test_parachute),
|
||||
|
||||
("ParameterChecks",
|
||||
"Test Arming Parameter Checks",
|
||||
self.test_parameter_checks),
|
||||
|
||||
("LogDownLoad",
|
||||
"Log download",
|
||||
lambda: self.log_download(
|
||||
|
Loading…
Reference in New Issue
Block a user