mirror of https://github.com/ArduPilot/ardupilot
Tools: autotest: Add sub test for MOT_THST_HOVER parameter
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
885ebc41e3
commit
98adeafad9
|
@ -141,6 +141,21 @@ class AutoTestSub(AutoTest):
|
||||||
|
|
||||||
self.disarm_vehicle()
|
self.disarm_vehicle()
|
||||||
|
|
||||||
|
def test_mot_thst_hover_ignore(self):
|
||||||
|
"""Test if we are ignoring MOT_THST_HOVER parameter
|
||||||
|
"""
|
||||||
|
|
||||||
|
# Test default parameter value
|
||||||
|
mot_thst_hover_value = self.get_parameter("MOT_THST_HOVER")
|
||||||
|
if mot_thst_hover_value != 0.5:
|
||||||
|
raise NotAchievedException("Unexpected default MOT_THST_HOVER parameter value {}".format(mot_thst_hover_value))
|
||||||
|
|
||||||
|
# Test if parameter is being ignored
|
||||||
|
for value in [0.25, 0.75]:
|
||||||
|
self.set_parameter("MOT_THST_HOVER", value)
|
||||||
|
self.test_alt_hold()
|
||||||
|
|
||||||
|
|
||||||
def dive_manual(self):
|
def dive_manual(self):
|
||||||
self.wait_ready_to_arm()
|
self.wait_ready_to_arm()
|
||||||
self.arm_vehicle()
|
self.arm_vehicle()
|
||||||
|
@ -287,6 +302,8 @@ class AutoTestSub(AutoTest):
|
||||||
"Test gripper mission items",
|
"Test gripper mission items",
|
||||||
self.test_gripper_mission),
|
self.test_gripper_mission),
|
||||||
|
|
||||||
|
("MotorThrustHoverParameterIgnore", "Test if we are ignoring MOT_THST_HOVER", self.test_mot_thst_hover_ignore),
|
||||||
|
|
||||||
("SET_POSITION_TARGET_GLOBAL_INT",
|
("SET_POSITION_TARGET_GLOBAL_INT",
|
||||||
"Move vehicle using SET_POSITION_TARGET_GLOBAL_INT",
|
"Move vehicle using SET_POSITION_TARGET_GLOBAL_INT",
|
||||||
self.dive_set_position_target),
|
self.dive_set_position_target),
|
||||||
|
|
Loading…
Reference in New Issue