mirror of https://github.com/ArduPilot/ardupilot
autotest: add test for Rover RTL speed
This commit is contained in:
parent
d93f9a09db
commit
7b95633bab
|
@ -525,6 +525,27 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
self.disarm_vehicle()
|
||||
self.progress("RTL Mission OK (%fm)" % home_distance)
|
||||
|
||||
def RTL_SPEED(self, timeout=120):
|
||||
'''Test RTL_SPEED is honoured'''
|
||||
|
||||
self.upload_simple_relhome_mission([
|
||||
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 300, 0, 0),
|
||||
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 0),
|
||||
])
|
||||
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
self.change_mode('AUTO')
|
||||
self.wait_current_waypoint(2, timeout=120)
|
||||
for speed in 1, 5.5, 1.5, 7.5:
|
||||
self.set_parameter("RTL_SPEED", speed)
|
||||
self.change_mode('RTL')
|
||||
self.wait_groundspeed(speed-0.1, speed+0.1, minimum_duration=10)
|
||||
self.change_mode('HOLD')
|
||||
self.do_RTL()
|
||||
self.disarm_vehicle()
|
||||
|
||||
def AC_Avoidance(self):
|
||||
'''Test AC Avoidance switch'''
|
||||
self.context_push()
|
||||
|
@ -6814,6 +6835,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
self.MAV_CMD_BATTERY_RESET,
|
||||
self.NetworkingWebServer,
|
||||
self.NetworkingWebServerPPP,
|
||||
self.RTL_SPEED,
|
||||
])
|
||||
return ret
|
||||
|
||||
|
|
Loading…
Reference in New Issue