mirror of https://github.com/ArduPilot/ardupilot
Autotest: Balance Bot changes to Acro after Auto mission instead of Loiter
This commit is contained in:
parent
c4182fc66b
commit
7933f94b2f
|
@ -450,7 +450,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') or self.mode_is('LOITER'): # loiter for balancebot
|
if self.mode_is('HOLD') or self.mode_is('ACRO'): # acro for balancebot
|
||||||
break
|
break
|
||||||
|
|
||||||
# the EKF doesn't pull us down to 0 speed:
|
# the EKF doesn't pull us down to 0 speed:
|
||||||
|
|
|
@ -43,8 +43,8 @@ class AutoTestBalanceBot(AutoTestRover):
|
||||||
|
|
||||||
def drive_rtl_mission(self):
|
def drive_rtl_mission(self):
|
||||||
# if we Hold then the balancebot continues to wander
|
# if we Hold then the balancebot continues to wander
|
||||||
# indefinitely at ~1m/s
|
# indefinitely at ~1m/s, hence we set to Acro
|
||||||
self.set_parameter("MIS_DONE_BEHAVE", 1)
|
self.set_parameter("MIS_DONE_BEHAVE", 2)
|
||||||
super(AutoTestBalanceBot, self).drive_rtl_mission()
|
super(AutoTestBalanceBot, self).drive_rtl_mission()
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
|
|
Loading…
Reference in New Issue