mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
autotest: augment Plane following test to ensure we terrain follow
This commit is contained in:
parent
0326d5eeca
commit
3bf76dbb64
@ -2753,15 +2753,26 @@ class AutoTestPlane(AutoTest):
|
||||
self.progress("loitering at %um" % alt)
|
||||
tstart = self.get_sim_time()
|
||||
timeout = 60*15 # enough time to do one and a bit circles
|
||||
max_delta = 0
|
||||
while True:
|
||||
now = self.get_sim_time_cached()
|
||||
if now - tstart > timeout:
|
||||
break
|
||||
gpi = self.assert_receive_message('GLOBAL_POSITION_INT')
|
||||
terrain = self.assert_receive_message('TERRAIN_REPORT')
|
||||
rel_alt = terrain.current_height
|
||||
self.progress("%um above terrain" % rel_alt)
|
||||
self.progress("%um above terrain (%um bove home)" %
|
||||
(rel_alt, gpi.relative_alt/1000.0))
|
||||
if rel_alt > alt*1.2 or rel_alt < alt * 0.8:
|
||||
raise NotAchievedException("Not terrain following")
|
||||
delta = abs(rel_alt - gpi.relative_alt/1000.0)
|
||||
if delta > max_delta:
|
||||
max_delta = delta
|
||||
want_max_delta = 30
|
||||
if max_delta < want_max_delta:
|
||||
raise NotAchievedException(
|
||||
"Expected terrain and home alts to vary more than they did (max=%u want=%u)" %
|
||||
(max_delta, want_max_delta))
|
||||
self.context_pop()
|
||||
self.progress("Returning home")
|
||||
self.fly_home_land_and_disarm(240)
|
||||
|
Loading…
Reference in New Issue
Block a user