mirror of https://github.com/ArduPilot/ardupilot
autotest: loosen takeoff check in heli takeoff to 1m
On the basis that random noise can make it drift 10cm
This commit is contained in:
parent
c40b5490f4
commit
d865c8553c
|
@ -5734,14 +5734,14 @@ class AutoTestHeli(AutoTestCopter):
|
|||
self.delay_sim_time(20)
|
||||
# check we are still on the ground...
|
||||
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
|
||||
max_relalt = 100
|
||||
if abs(m.relative_alt) > max_relalt:
|
||||
max_relalt_mm = 1000
|
||||
if abs(m.relative_alt) > max_relalt_mm:
|
||||
raise NotAchievedException("Took off prematurely (abs(%f)>%f)" %
|
||||
(m.relative_alt, max_relalt))
|
||||
self.progress("Pushing throttle past half-way")
|
||||
(m.relative_alt, max_relalt_mm))
|
||||
self.progress("Pushing collective past half-way")
|
||||
self.set_rc(3, 1600)
|
||||
self.delay_sim_time(0.5)
|
||||
self.progress("Bringing back to hover throttle")
|
||||
self.progress("Bringing back to hover collective")
|
||||
self.set_rc(3, 1500)
|
||||
|
||||
# make sure we haven't already reached alt:
|
||||
|
@ -5763,6 +5763,8 @@ class AutoTestHeli(AutoTestCopter):
|
|||
raise NotAchievedException("Failed to maintain takeoff alt")
|
||||
self.progress("takeoff OK")
|
||||
except Exception as e:
|
||||
self.progress("Caught exception: %s" %
|
||||
self.get_exception_stacktrace(e))
|
||||
ex = e
|
||||
|
||||
self.land_and_disarm()
|
||||
|
@ -5771,8 +5773,6 @@ class AutoTestHeli(AutoTestCopter):
|
|||
self.context_pop()
|
||||
|
||||
if ex is not None:
|
||||
self.progress("Caught exception: %s" %
|
||||
self.get_exception_stacktrace(ex))
|
||||
raise ex
|
||||
|
||||
def fly_heli_stabilize_takeoff(self):
|
||||
|
|
Loading…
Reference in New Issue