Tools: autotest: fix balancebot RTL test

This commit is contained in:
Peter Barker 2019-03-10 10:39:10 +11:00 committed by Peter Barker
parent 0215e08f86
commit 4f136512f0
2 changed files with 21 additions and 31 deletions

View File

@ -387,6 +387,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
"Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" % "Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" %
(distance_with_brakes, distance_without_brakes, delta)) (distance_with_brakes, distance_without_brakes, delta))
def drive_rtl_mission_max_distance_from_home(self):
'''maximum distance allowed from home at end'''
return 6.5
def drive_rtl_mission(self): def drive_rtl_mission(self):
self.wait_ready_to_arm() self.wait_ready_to_arm()
self.arm_vehicle() self.arm_vehicle()
@ -408,8 +412,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
wp_dist_min = 5 wp_dist_min = 5
if m.wp_dist < wp_dist_min: if m.wp_dist < wp_dist_min:
raise PreconditionFailedException( raise PreconditionFailedException(
"Did not start at least %u metres from destination" % "Did not start at least %f metres from destination (is=%f)" %
(wp_dist_min)) (wp_dist_min, m.wp_dist))
self.progress("NAV_CONTROLLER_OUTPUT.wp_dist looks good (%u >= %u)" % self.progress("NAV_CONTROLLER_OUTPUT.wp_dist looks good (%u >= %u)" %
(m.wp_dist, wp_dist_min,)) (m.wp_dist, wp_dist_min,))
@ -420,7 +424,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
raise NotAchievedException("Did not get home") raise NotAchievedException("Did not get home")
self.progress("Distance home: %f (mode=%s)" % self.progress("Distance home: %f (mode=%s)" %
(self.distance_to_home(), self.mav.flightmode)) (self.distance_to_home(), self.mav.flightmode))
if self.mode_is('HOLD'): if self.mode_is('HOLD') or self.mode_is('LOITER'): # loiter for balancebot
break break
# the EKF doesn't pull us down to 0 speed: # the EKF doesn't pull us down to 0 speed:
@ -430,7 +434,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
# up ~6m past the home point. # up ~6m past the home point.
home_distance = self.distance_to_home() home_distance = self.distance_to_home()
home_distance_min = 5.5 home_distance_min = 5.5
home_distance_max = 6.5 home_distance_max = self.drive_rtl_mission_max_distance_from_home()
if home_distance > home_distance_max: if home_distance > home_distance_max:
raise NotAchievedException( raise NotAchievedException(
"Did not stop near home (%f metres distant (%f > want > %f))" % "Did not stop near home (%f metres distant (%f > want > %f))" %

View File

@ -4,42 +4,17 @@
from __future__ import print_function from __future__ import print_function
import os import os
import pexpect
from apmrover2 import AutoTestRover from apmrover2 import AutoTestRover
from common import AutoTest from common import AutoTest
from pymavlink import mavutil
# get location of scripts # get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__)) testdir = os.path.dirname(os.path.realpath(__file__))
# HOME = mavutil.location(-35.362938, 149.165085, 584, 270) def log_name(self):
HOME = mavutil.location(40.071374969556928, return "BalanceBot"
-105.22978898137808,
1583.702759,
246)
class AutoTestBalanceBot(AutoTestRover): class AutoTestBalanceBot(AutoTestRover):
def __init__(self,
binary,
valgrind=False,
gdb=False,
speedup=10,
frame=None,
params=None,
gdbserver=False,
**kwargs):
super(AutoTestBalanceBot, self).__init__(binary,
valgrind,
gdb,
speedup,
frame,
params,
gdbserver,
**kwargs)
self.log_name = "BalanceBot"
def vehicleinfo_key(self): def vehicleinfo_key(self):
return "APMrover2" return "APMrover2"
@ -61,6 +36,17 @@ class AutoTestBalanceBot(AutoTestRover):
def is_balancebot(self): def is_balancebot(self):
return True return True
def drive_rtl_mission_max_distance_from_home(self):
'''maximum distance allowed from home at end'''
'''balancebot tends to wander backwards, away from the target'''
return 8
def drive_rtl_mission(self):
# if we Hold then the balancebot continues to wander
# indefinitely at ~1m/s
self.set_parameter("MIS_DONE_BEHAVE", 1)
super(AutoTestBalanceBot, self).drive_rtl_mission()
def tests(self): def tests(self):
'''return list of all tests''' '''return list of all tests'''