autotest: rename set_heartbeat_interval to set_heartbeat_rate

This commit is contained in:
Peter Barker 2020-06-03 17:00:38 +10:00 committed by Peter Barker
parent cab3630009
commit 6c67ddacf4

View File

@ -194,8 +194,8 @@ class AutoTestCopter(AutoTest):
self.progress("Cotper staging 50 meters east of home at 50 meters altitude In mode Alt Hold") 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 # Start and stop the GCS heartbeat for GCS failsafe testing
def set_heartbeat_interval(self, interval): def set_heartbeat_rate(self, rate):
self.mavproxy.send('set heartbeat %u\n' % interval) self.mavproxy.send('set heartbeat %u\n' % rate)
# loiter - fly south west, then loiter within 5m position and altitude # loiter - fly south west, then loiter within 5m position and altitude
def loiter(self, holdtime=10, maxaltchange=5, maxdistchange=5): def loiter(self, holdtime=10, maxaltchange=5, maxdistchange=5):
@ -676,10 +676,10 @@ class AutoTestCopter(AutoTest):
self.start_subtest("GCS failsafe disabled test: FS_GCS_ENABLE=0 should take no failsafe action") self.start_subtest("GCS failsafe disabled test: FS_GCS_ENABLE=0 should take no failsafe action")
self.setGCSfailsafe(0) self.setGCSfailsafe(0)
self.takeoffAndMoveAway() self.takeoffAndMoveAway()
self.set_heartbeat_interval(0) self.set_heartbeat_rate(0)
self.delay_sim_time(5) self.delay_sim_time(5)
self.wait_mode("ALT_HOLD") self.wait_mode("ALT_HOLD")
self.set_heartbeat_interval(self.speedup) self.set_heartbeat_rate(self.speedup)
self.delay_sim_time(5) self.delay_sim_time(5)
self.wait_mode("ALT_HOLD") self.wait_mode("ALT_HOLD")
self.end_subtest("Completed GCS failsafe disabled test") self.end_subtest("Completed GCS failsafe disabled test")
@ -687,19 +687,19 @@ class AutoTestCopter(AutoTest):
# Trigger telemetry loss with failsafe enabled. Verify failsafe tirggers to RTL. Restory telemety, verify failsafe clears, and change modes. # 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.start_subtest("GCS failsafe recovery test")
self.setGCSfailsafe(1) self.setGCSfailsafe(1)
self.set_heartbeat_interval(0) self.set_heartbeat_rate(0)
self.wait_mode("RTL") self.wait_mode("RTL")
self.set_heartbeat_interval(self.speedup) self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared") self.mavproxy.expect("GCS Failsafe Cleared")
self.change_mode("LOITER") self.change_mode("LOITER")
self.end_subtest("Completed GCS failsafe recovery test") self.end_subtest("Completed GCS failsafe recovery test")
# Trigger telemetry loss with failsafe enabled. Verify failsafe tirggers and RTL completes # 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.start_subtest("GCS failsafe RTL with no options test: FS_GCS_ENABLE=1 & FS_OPTIONS=0")
self.set_heartbeat_interval(0) self.set_heartbeat_rate(0)
self.wait_mode("RTL") self.wait_mode("RTL")
self.wait_disarmed() self.wait_disarmed()
self.set_heartbeat_interval(self.speedup) self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared") self.mavproxy.expect("GCS Failsafe Cleared")
self.end_subtest("Completed GCS failsafe RTL with no options test") self.end_subtest("Completed GCS failsafe RTL with no options test")
@ -707,10 +707,10 @@ class AutoTestCopter(AutoTest):
self.start_subtest("GCS failsafe LAND with no options test: FS_GCS_ENABLE=5 & FS_OPTIONS=0") self.start_subtest("GCS failsafe LAND with no options test: FS_GCS_ENABLE=5 & FS_OPTIONS=0")
self.setGCSfailsafe(5) self.setGCSfailsafe(5)
self.takeoffAndMoveAway() self.takeoffAndMoveAway()
self.set_heartbeat_interval(0) self.set_heartbeat_rate(0)
self.wait_mode("LAND") self.wait_mode("LAND")
self.wait_disarmed() self.wait_disarmed()
self.set_heartbeat_interval(self.speedup) self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared") self.mavproxy.expect("GCS Failsafe Cleared")
self.end_subtest("Completed GCS failsafe land with no options test") self.end_subtest("Completed GCS failsafe land with no options test")
@ -718,10 +718,10 @@ class AutoTestCopter(AutoTest):
self.start_subtest("GCS failsafe SmartRTL->RTL with no options test: FS_GCS_ENABLE=3 & FS_OPTIONS=0") self.start_subtest("GCS failsafe SmartRTL->RTL with no options test: FS_GCS_ENABLE=3 & FS_OPTIONS=0")
self.setGCSfailsafe(3) self.setGCSfailsafe(3)
self.takeoffAndMoveAway() self.takeoffAndMoveAway()
self.set_heartbeat_interval(0) self.set_heartbeat_rate(0)
self.wait_mode("SMART_RTL") self.wait_mode("SMART_RTL")
self.wait_disarmed() self.wait_disarmed()
self.set_heartbeat_interval(self.speedup) self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared") self.mavproxy.expect("GCS Failsafe Cleared")
self.end_subtest("Completed GCS failsafe SmartRTL->RTL with no options test") self.end_subtest("Completed GCS failsafe SmartRTL->RTL with no options test")
@ -729,10 +729,10 @@ class AutoTestCopter(AutoTest):
self.start_subtest("GCS failsafe SmartRTL->Land with no options test: FS_GCS_ENABLE=4 & FS_OPTIONS=0") self.start_subtest("GCS failsafe SmartRTL->Land with no options test: FS_GCS_ENABLE=4 & FS_OPTIONS=0")
self.setGCSfailsafe(4) self.setGCSfailsafe(4)
self.takeoffAndMoveAway() self.takeoffAndMoveAway()
self.set_heartbeat_interval(0) self.set_heartbeat_rate(0)
self.wait_mode("SMART_RTL") self.wait_mode("SMART_RTL")
self.wait_disarmed() self.wait_disarmed()
self.set_heartbeat_interval(self.speedup) self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared") self.mavproxy.expect("GCS Failsafe Cleared")
self.end_subtest("Completed GCS failsafe SmartRTL->Land with no options test") self.end_subtest("Completed GCS failsafe SmartRTL->Land with no options test")
@ -740,10 +740,10 @@ class AutoTestCopter(AutoTest):
self.start_subtest("GCS failsafe invalid value with no options test: FS_GCS_ENABLE=99 & FS_OPTIONS=0") self.start_subtest("GCS failsafe invalid value with no options test: FS_GCS_ENABLE=99 & FS_OPTIONS=0")
self.setGCSfailsafe(99) self.setGCSfailsafe(99)
self.takeoffAndMoveAway() self.takeoffAndMoveAway()
self.set_heartbeat_interval(0) self.set_heartbeat_rate(0)
self.wait_mode("RTL") self.wait_mode("RTL")
self.wait_disarmed() self.wait_disarmed()
self.set_heartbeat_interval(self.speedup) self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared") self.mavproxy.expect("GCS Failsafe Cleared")
self.end_subtest("Completed GCS failsafe invalid value with no options test") self.end_subtest("Completed GCS failsafe invalid value with no options test")
@ -756,34 +756,34 @@ class AutoTestCopter(AutoTest):
self.set_parameter('FS_OPTIONS', 16) self.set_parameter('FS_OPTIONS', 16)
self.takeoffAndMoveAway() self.takeoffAndMoveAway()
self.progress("Testing continue in pilot controlled modes") self.progress("Testing continue in pilot controlled modes")
self.set_heartbeat_interval(0) self.set_heartbeat_rate(0)
self.mavproxy.expect("GCS Failsafe - Continuing Pilot Control") self.mavproxy.expect("GCS Failsafe - Continuing Pilot Control")
self.delay_sim_time(5) self.delay_sim_time(5)
self.wait_mode("ALT_HOLD") self.wait_mode("ALT_HOLD")
self.set_heartbeat_interval(self.speedup) self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared") self.mavproxy.expect("GCS Failsafe Cleared")
self.progress("Testing continue in auto mission") self.progress("Testing continue in auto mission")
self.set_parameter('FS_OPTIONS', 2) self.set_parameter('FS_OPTIONS', 2)
self.change_mode("AUTO") self.change_mode("AUTO")
self.delay_sim_time(5) self.delay_sim_time(5)
self.set_heartbeat_interval(0) self.set_heartbeat_rate(0)
self.mavproxy.expect("GCS Failsafe - Continuing Auto Mode") self.mavproxy.expect("GCS Failsafe - Continuing Auto Mode")
self.delay_sim_time(5) self.delay_sim_time(5)
self.wait_mode("AUTO") self.wait_mode("AUTO")
self.set_heartbeat_interval(self.speedup) self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared") self.mavproxy.expect("GCS Failsafe Cleared")
self.progress("Testing continue landing in land mode") self.progress("Testing continue landing in land mode")
self.set_parameter('FS_OPTIONS', 8) self.set_parameter('FS_OPTIONS', 8)
self.change_mode("LAND") self.change_mode("LAND")
self.delay_sim_time(5) self.delay_sim_time(5)
self.set_heartbeat_interval(0) self.set_heartbeat_rate(0)
self.mavproxy.expect("GCS Failsafe - Continuing Landing") self.mavproxy.expect("GCS Failsafe - Continuing Landing")
self.delay_sim_time(5) self.delay_sim_time(5)
self.wait_mode("LAND") self.wait_mode("LAND")
self.wait_disarmed() self.wait_disarmed()
self.set_heartbeat_interval(self.speedup) self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared") self.mavproxy.expect("GCS Failsafe Cleared")
self.end_subtest("Completed GCS failsafe with option bits") self.end_subtest("Completed GCS failsafe with option bits")