Skip to content

Commit

Permalink
Tools: copter: add wait land and disarm functions
Browse files Browse the repository at this point in the history
  • Loading branch information
khancyr authored and peterbarker committed Aug 29, 2020
1 parent 3b5bd99 commit 3080899
Showing 1 changed file with 24 additions and 30 deletions.
54 changes: 24 additions & 30 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,11 @@ def land_and_disarm(self, timeout=60):
"""Land the quad."""
self.progress("STARTING LANDING")
self.change_mode("LAND")
self.wait_altitude(-5, 1, relative=True, timeout=timeout)
self.wait_landed_and_disarmed(timeout=timeout)

def wait_landed_and_disarmed(self, min_alt=4, timeout=60):
"""Wait to be landed and disarmed"""
self.wait_altitude(-5, min_alt, relative=True, timeout=timeout)
self.progress("LANDING: ok!")
self.wait_disarmed()

Expand Down Expand Up @@ -396,8 +400,7 @@ def fly_square(self, side=50, timeout=300):
self.change_mode('AUTO')
self.wait_waypoint(0, num_wp-1, timeout=500)
self.progress("test: MISSION COMPLETE: passed!")
self.change_mode('LAND')
self.wait_disarmed()
self.land_and_disarm()

# enter RTL mode and wait for the vehicle to disarm
def do_RTL(self, distance_min=None, distance_max=10, timeout=250):
Expand Down Expand Up @@ -520,7 +523,7 @@ def fly_throttle_failsafe(self, side=60, timeout=360):
self.takeoffAndMoveAway()
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_mode("LAND")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.set_parameter("SIM_RC_FAIL", 0)
self.end_subtest("Completed Radio failsafe LAND with no options test")

Expand Down Expand Up @@ -552,7 +555,7 @@ def fly_throttle_failsafe(self, side=60, timeout=360):
self.delay_sim_time(5)
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_mode("LAND")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.set_parameter("SIM_RC_FAIL", 0)
self.set_parameter('SIM_GPS_DISABLE', 0)
self.wait_ekf_happy()
Expand All @@ -566,7 +569,7 @@ def fly_throttle_failsafe(self, side=60, timeout=360):
self.delay_sim_time(5)
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_mode("LAND")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.set_parameter("SIM_RC_FAIL", 0)
self.set_parameter('SIM_GPS_DISABLE', 0)
self.wait_ekf_happy()
Expand All @@ -580,7 +583,7 @@ def fly_throttle_failsafe(self, side=60, timeout=360):
self.delay_sim_time(5)
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_mode("LAND")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.set_parameter("SIM_RC_FAIL", 0)
self.set_parameter('SIM_GPS_DISABLE', 0)
self.wait_ekf_happy()
Expand Down Expand Up @@ -612,7 +615,7 @@ def fly_throttle_failsafe(self, side=60, timeout=360):
self.delay_sim_time(5)
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_mode("LAND")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.set_parameter("SIM_RC_FAIL", 0)
self.end_subtest("Completed Radio failsafe SmartRTL->LAND fails into land mode due to no path.")

Expand Down Expand Up @@ -715,7 +718,7 @@ def test_gcs_failsafe(self, side=60, timeout=360):
self.takeoffAndMoveAway()
self.set_heartbeat_rate(0)
self.wait_mode("LAND")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.end_subtest("Completed GCS failsafe land with no options test")
Expand Down Expand Up @@ -788,7 +791,7 @@ def test_gcs_failsafe(self, side=60, timeout=360):
self.mavproxy.expect("GCS Failsafe - Continuing Landing")
self.delay_sim_time(5)
self.wait_mode("LAND")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.end_subtest("Completed GCS failsafe with option bits")
Expand Down Expand Up @@ -858,7 +861,7 @@ def test_battery_failsafe(self, timeout=300):
self.mavproxy.expect("Battery 1 is critical")
self.delay_sim_time(5)
self.wait_mode("LAND")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
self.reboot_sitl_mavproxy()
self.end_subtest("Completed two stage battery failsafe test with RTL and Land")
Expand Down Expand Up @@ -894,7 +897,7 @@ def test_battery_failsafe(self, timeout=300):
self.mavproxy.expect("Battery 1 is low")
self.delay_sim_time(5)
self.wait_mode("LAND")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
self.reboot_sitl_mavproxy()
self.end_subtest("Completed battery failsafe with FS_OPTIONS set to continue landing")
Expand All @@ -914,7 +917,7 @@ def test_battery_failsafe(self, timeout=300):
self.set_parameter("SIM_RC_FAIL", 1)
self.delay_sim_time(10)
self.wait_mode("LAND")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
self.set_parameter("SIM_RC_FAIL", 0)
self.reboot_sitl_mavproxy()
Expand Down Expand Up @@ -1190,8 +1193,7 @@ def fly_fence_test(self, timeout=180):
# reduce throttle
self.zero_throttle()
self.change_mode("LAND")
self.progress("Waiting for disarm")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.progress("Reached home OK")
self.zero_throttle()
return
Expand Down Expand Up @@ -1718,7 +1720,7 @@ def fly_autotune(self):
self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart))
# near enough for now:
self.change_mode('LAND')
self.wait_disarmed()
self.wait_landed_and_disarmed()
# check the original gains have been re-instated
if (rlld != self.get_parameter("ATC_RAT_RLL_D")
or rlli != self.get_parameter("ATC_RAT_RLL_I")
Expand Down Expand Up @@ -2551,7 +2553,7 @@ def fly_precision_sitl(self):
self.zero_throttle()
self.takeoff(10, 1800)
self.change_mode("LAND")
self.wait_disarmed()
self.wait_landed_and_disarmed()
self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
new_pos = self.mav.location()
delta = self.get_distance(target, new_pos)
Expand Down Expand Up @@ -4384,7 +4386,7 @@ def test_altitude_types(self):
self.fly_guided_move_to(low_position, timeout=240)
self.change_mode('LAND')
# expecting home to change when disarmed
self.wait_disarmed()
self.wait_landed_and_disarmed()
# wait a while for home to move (it shouldn't):
self.delay_sim_time(10)
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
Expand Down Expand Up @@ -4567,9 +4569,7 @@ def fly_poshold_takeoff(self):
except Exception as e:
ex = e

self.mavproxy.send('mode LAND\n')
self.wait_mode('LAND')
self.wait_disarmed()
self.land_and_disarm()
self.set_rc(8, 1000)

self.context_pop()
Expand Down Expand Up @@ -5567,9 +5567,7 @@ def rotor_runup_complete_checks(self):
self.progress("Runup time %u" % runup_time)
self.zero_throttle()
self.set_rc(8, 1000)
self.mavproxy.send('mode LAND\n')
self.wait_mode('LAND')
self.mav.motors_disarmed_wait()
self.land_and_disarm()
self.mav.wait_heartbeat()

# fly_avc_test - fly AVC mission
Expand Down Expand Up @@ -5667,9 +5665,7 @@ def fly_heli_poshold_takeoff(self):
except Exception as e:
ex = e

self.mavproxy.send('mode LAND\n')
self.wait_mode('LAND')
self.wait_disarmed()
self.land_and_disarm()
self.set_rc(8, 1000)

self.context_pop()
Expand Down Expand Up @@ -5708,9 +5704,7 @@ def fly_heli_stabilize_takeoff(self):
except Exception as e:
ex = e

self.mavproxy.send('mode LAND\n')
self.wait_mode('LAND')
self.wait_disarmed()
self.land_and_disarm()
self.set_rc(8, 1000)

self.context_pop()
Expand Down

0 comments on commit 3080899

Please sign in to comment.