autotest: set RL_AUTOLAND=1 for more tests

This commit is contained in:
Peter Barker 2022-03-13 15:16:27 +11:00 committed by Andrew Tridgell
parent 46a7f2cc4b
commit 573cb0494d
1 changed files with 17 additions and 5 deletions

View File

@ -570,9 +570,12 @@ class AutoTestPlane(AutoTest):
def fly_deepstall_absolute(self):
self.start_subtest("DeepStall Relative Absolute")
self.set_parameter("LAND_TYPE", 1)
deepstall_elevator_pwm = 1661
self.set_parameter("LAND_DS_ELEV_PWM", deepstall_elevator_pwm)
self.set_parameters({
"LAND_TYPE": 1,
"LAND_DS_ELEV_PWM": deepstall_elevator_pwm,
"RTL_AUTOLAND": 1,
})
self.load_mission("plane-deepstall-mission.txt")
self.change_mode("AUTO")
self.wait_ready_to_arm()
@ -593,9 +596,12 @@ class AutoTestPlane(AutoTest):
def fly_deepstall_relative(self):
self.start_subtest("DeepStall Relative")
self.set_parameter("LAND_TYPE", 1)
deepstall_elevator_pwm = 1661
self.set_parameter("LAND_DS_ELEV_PWM", deepstall_elevator_pwm)
self.set_parameters({
"LAND_TYPE": 1,
"LAND_DS_ELEV_PWM": deepstall_elevator_pwm,
"RTL_AUTOLAND": 1,
})
self.load_mission("plane-deepstall-relative-mission.txt")
self.change_mode("AUTO")
self.wait_ready_to_arm()
@ -1096,6 +1102,7 @@ class AutoTestPlane(AutoTest):
self.context_push()
ex = None
try:
self.set_parameter("RTL_AUTOLAND", 1)
self.load_mission("plane-gripper-mission.txt")
self.set_current_waypoint(1)
self.change_mode('AUTO')
@ -1642,7 +1649,10 @@ class AutoTestPlane(AutoTest):
def airspeed_autocal(self):
self.progress("Ensure no AIRSPEED_AUTOCAL on ground")
self.set_parameter("ARSPD_AUTOCAL", 1)
self.set_parameters({
"ARSPD_AUTOCAL": 1,
"RTL_AUTOLAND": 1,
})
m = self.mav.recv_match(type='AIRSPEED_AUTOCAL',
blocking=True,
timeout=5)
@ -1740,6 +1750,7 @@ class AutoTestPlane(AutoTest):
self.set_parameters({
"FLIGHT_OPTIONS": 0,
"ALT_HOLD_RTL": 8000,
"RTL_AUTOLAND": 1,
})
takeoff_alt = 10
self.takeoff(alt=takeoff_alt)
@ -1858,6 +1869,7 @@ class AutoTestPlane(AutoTest):
'''ensure rangefinder gives height-above-ground'''
self.load_mission("plane-gripper-mission.txt") # borrow this
self.set_parameter("RTL_AUTOLAND", 1)
self.set_current_waypoint(1)
self.change_mode('AUTO')
self.wait_ready_to_arm()