mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AutoTest: Copter: fly_poshold_takeoff increase acceptable range
This commit is contained in:
parent
c91fdcea72
commit
41c437b768
@ -5065,7 +5065,7 @@ class AutoTestCopter(AutoTest):
|
||||
|
||||
# make sure we haven't already reached alt:
|
||||
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
|
||||
max_initial_alt = 500
|
||||
max_initial_alt = 2000
|
||||
if abs(m.relative_alt) > max_initial_alt:
|
||||
raise NotAchievedException("Took off too fast (%f > %f" %
|
||||
(abs(m.relative_alt), max_initial_alt))
|
||||
@ -7265,6 +7265,7 @@ class AutoTestHeli(AutoTestCopter):
|
||||
if abs(m.relative_alt) > max_relalt_mm:
|
||||
raise NotAchievedException("Took off prematurely (abs(%f)>%f)" %
|
||||
(m.relative_alt, max_relalt_mm))
|
||||
|
||||
self.progress("Pushing collective past half-way")
|
||||
self.set_rc(3, 1600)
|
||||
self.delay_sim_time(0.5)
|
||||
@ -7273,8 +7274,10 @@ class AutoTestHeli(AutoTestCopter):
|
||||
|
||||
# make sure we haven't already reached alt:
|
||||
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
|
||||
if abs(m.relative_alt) > 500:
|
||||
raise NotAchievedException("Took off too fast")
|
||||
max_initial_alt = 1500
|
||||
if abs(m.relative_alt) > max_initial_alt:
|
||||
raise NotAchievedException("Took off too fast (%f > %f" %
|
||||
(abs(m.relative_alt), max_initial_alt))
|
||||
|
||||
self.progress("Monitoring takeoff-to-alt")
|
||||
self.wait_altitude(6.9, 8, relative=True)
|
||||
|
Loading…
Reference in New Issue
Block a user