mirror of https://github.com/ArduPilot/ardupilot
autotest: set RL_AUTOLAND=1 for more tests
This commit is contained in:
parent
4003ddb2cb
commit
f93f8daee7
|
@ -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()
|
||||
|
@ -1075,6 +1081,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')
|
||||
|
@ -1621,7 +1628,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)
|
||||
|
@ -1719,6 +1729,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)
|
||||
|
@ -1837,6 +1848,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()
|
||||
|
|
Loading…
Reference in New Issue