From 74eb6760ea02afb8f895572ecbbf242b2a518662 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Nov 2019 17:16:50 +1100 Subject: [PATCH] autotest: correct setHeatbeat -> setHeartbeat --- Tools/autotest/arducopter.py | 42 ++++++++++++++++++------------------ 1 file changed, 21 insertions(+), 21 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 2ad5dfdeae..f534cad843 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -187,7 +187,7 @@ class AutoTestCopter(AutoTest): self.progress("Cotper staging 50 meters east of home at 50 meters altitude In mode Alt Hold") # Start and stop the GCS heartbeat for GCS failsafe testing - def setHearbeat(self, beating=True): + def setHeartbeat(self, beating=True): if beating == False: self.mavproxy.send('set heartbeat 0\n') else: @@ -664,10 +664,10 @@ class AutoTestCopter(AutoTest): self.start_subtest("GCS failsafe disabled test: FS_GCS_ENABLE=0 should take no failsafe action") self.setGCSfailsafe(0) self.takeoffAndMoveAway() - self.setHearbeat(False) + self.setHeartbeat(False) self.wait_seconds(5) self.wait_mode("ALT_HOLD") - self.setHearbeat() + self.setHeartbeat() self.wait_seconds(5) self.wait_mode("ALT_HOLD") self.end_subtest("Completed GCS failsafe disabled test") @@ -675,19 +675,19 @@ class AutoTestCopter(AutoTest): # Trigger telemetry loss with failsafe enabled. Verify failsafe tirggers to RTL. Restory telemety, verify failsafe clears, and change modes. self.start_subtest("GCS failsafe recovery test") self.setGCSfailsafe(1) - self.setHearbeat(False) + self.setHeartbeat(False) self.wait_mode("RTL") - self.setHearbeat() + self.setHeartbeat() self.mavproxy.expect("GCS Failsafe Cleared") self.change_mode("LOITER") self.end_subtest("Completed GCS failsafe recovery test") # Trigger telemetry loss with failsafe enabled. Verify failsafe tirggers and RTL completes self.start_subtest("GCS failsafe RTL with no options test: FS_GCS_ENABLE=1 & FS_OPTIONS=0") - self.setHearbeat(False) + self.setHeartbeat(False) self.wait_mode("RTL") self.mav.motors_disarmed_wait() - self.setHearbeat() + self.setHeartbeat() self.mavproxy.expect("GCS Failsafe Cleared") self.end_subtest("Completed GCS failsafe RTL with no options test") @@ -695,10 +695,10 @@ class AutoTestCopter(AutoTest): self.start_subtest("GCS failsafe LAND with no options test: FS_GCS_ENABLE=5 & FS_OPTIONS=0") self.setGCSfailsafe(5) self.takeoffAndMoveAway() - self.setHearbeat(False) + self.setHeartbeat(False) self.wait_mode("LAND") self.mav.motors_disarmed_wait() - self.setHearbeat() + self.setHeartbeat() self.mavproxy.expect("GCS Failsafe Cleared") self.end_subtest("Completed GCS failsafe land with no options test") @@ -706,10 +706,10 @@ class AutoTestCopter(AutoTest): self.start_subtest("GCS failsafe SmartRTL->RTL with no options test: FS_GCS_ENABLE=3 & FS_OPTIONS=0") self.setGCSfailsafe(3) self.takeoffAndMoveAway() - self.setHearbeat(False) + self.setHeartbeat(False) self.wait_mode("SMART_RTL") self.mav.motors_disarmed_wait() - self.setHearbeat() + self.setHeartbeat() self.mavproxy.expect("GCS Failsafe Cleared") self.end_subtest("Completed GCS failsafe SmartRTL->RTL with no options test") @@ -717,10 +717,10 @@ class AutoTestCopter(AutoTest): self.start_subtest("GCS failsafe SmartRTL->Land with no options test: FS_GCS_ENABLE=4 & FS_OPTIONS=0") self.setGCSfailsafe(4) self.takeoffAndMoveAway() - self.setHearbeat(False) + self.setHeartbeat(False) self.wait_mode("SMART_RTL") self.mav.motors_disarmed_wait() - self.setHearbeat() + self.setHeartbeat() self.mavproxy.expect("GCS Failsafe Cleared") self.end_subtest("Completed GCS failsafe SmartRTL->Land with no options test") @@ -728,10 +728,10 @@ class AutoTestCopter(AutoTest): self.start_subtest("GCS failsafe invalid value with no options test: FS_GCS_ENABLE=99 & FS_OPTIONS=0") self.setGCSfailsafe(99) self.takeoffAndMoveAway() - self.setHearbeat(False) + self.setHeartbeat(False) self.wait_mode("RTL") self.mav.motors_disarmed_wait() - self.setHearbeat() + self.setHeartbeat() self.mavproxy.expect("GCS Failsafe Cleared") self.end_subtest("Completed GCS failsafe invalid value with no options test") @@ -744,34 +744,34 @@ class AutoTestCopter(AutoTest): self.set_parameter('FS_OPTIONS', 16) self.takeoffAndMoveAway() self.progress("Testing continue in pilot controlled modes") - self.setHearbeat(False) + self.setHeartbeat(False) self.mavproxy.expect("GCS Failsafe - Continuing Pilot Control") self.wait_seconds(5) self.wait_mode("ALT_HOLD") - self.setHearbeat() + self.setHeartbeat() self.mavproxy.expect("GCS Failsafe Cleared") self.progress("Testing continue in auto mission") self.set_parameter('FS_OPTIONS', 2) self.change_mode("AUTO") self.wait_seconds(5) - self.setHearbeat(False) + self.setHeartbeat(False) self.mavproxy.expect("GCS Failsafe - Continuing Auto Mode") self.wait_seconds(5) self.wait_mode("AUTO") - self.setHearbeat() + self.setHeartbeat() self.mavproxy.expect("GCS Failsafe Cleared") self.progress("Testing continue landing in land mode") self.set_parameter('FS_OPTIONS', 8) self.change_mode("LAND") self.wait_seconds(5) - self.setHearbeat(False) + self.setHeartbeat(False) self.mavproxy.expect("GCS Failsafe - Continuing Landing") self.wait_seconds(5) self.wait_mode("LAND") self.mav.motors_disarmed_wait() - self.setHearbeat() + self.setHeartbeat() self.mavproxy.expect("GCS Failsafe Cleared") self.end_subtest("Completed GCS failsafe with option bits")