Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

autotest: Cache terrain data within autotest directory #21323

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
*.vbrain
*.vrx
*.zip
!Tools/autotest/tilecache/**/*.zip
*~
.*.swo
.*.swp
Expand Down
19 changes: 4 additions & 15 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -487,9 +487,8 @@ def fly_loiter_to_alt(self):

self.change_mode('LOITER')

mavproxy = self.start_mavproxy()
self.wait_ready_to_arm(timeout=120*60) # terrain takes time
self.stop_mavproxy(mavproxy)
self.install_terrain_handlers_context()
self.wait_ready_to_arm()

self.arm_vehicle()

Expand Down Expand Up @@ -3224,10 +3223,7 @@ def test_surface_tracking(self):
ex = None
self.context_push()

# we must start mavproxy here as otherwise we can't get the
# terrain database tiles - this leads to random failures in
# CI!
mavproxy = self.start_mavproxy()
self.install_terrain_handlers_context()

try:
self.set_analog_rangefinder_parameters()
Expand Down Expand Up @@ -3277,8 +3273,6 @@ def test_surface_tracking(self):
self.disarm_vehicle(force=True)
ex = e

self.stop_mavproxy(mavproxy)

self.context_pop()
self.reboot_sitl()
if ex is not None:
Expand Down Expand Up @@ -5825,10 +5819,7 @@ def test_altitude_types(self):

'''

# we must start mavproxy here as otherwise we can't get the
# terrain database tiles - this leads to random failures in
# CI!
mavproxy = self.start_mavproxy()
self.install_terrain_handlers_context()

self.set_parameter("FS_GCS_ENABLE", 0)
self.change_mode('GUIDED')
Expand Down Expand Up @@ -5889,8 +5880,6 @@ def test_altitude_types(self):

self.wait_disarmed()

self.stop_mavproxy(mavproxy)

def PrecisionLoiterCompanion(self):
"""Use Companion PrecLand backend precision messages to loiter."""

Expand Down
10 changes: 3 additions & 7 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -2565,11 +2565,11 @@ def check_airspeeds(mav, m):

def TerrainMission(self):

mavproxy = self.start_mavproxy()
self.install_terrain_handlers_context()

num_wp = self.load_mission("ap-terrain.txt")

self.wait_ready_to_arm(timeout=120*60) # time to get terrain
self.wait_ready_to_arm()
self.arm_vehicle()

global max_alt
Expand All @@ -2586,16 +2586,14 @@ def record_maxalt(mav, m):

self.fly_mission_waypoints(num_wp-1, mission_timeout=600)

self.stop_mavproxy(mavproxy)

if max_alt < 200:
raise NotAchievedException("Did not follow terrain")

def Terrain(self):
'''test AP_Terrain'''
self.reboot_sitl() # we know the terrain height at CMAC

mavproxy = self.start_mavproxy()
self.install_terrain_handlers_context()

self.wait_ready_to_arm()
loc = self.mav.location()
Expand Down Expand Up @@ -2636,8 +2634,6 @@ def Terrain(self):
raise NotAchievedException("Expected terrain height=%f got=%f" %
(expected_terrain_height, report.terrain_height))

self.stop_mavproxy(mavproxy)

def test_loiter_terrain(self):
default_rad = self.get_parameter("WP_LOITER_RAD")
self.set_parameters({
Expand Down
83 changes: 71 additions & 12 deletions Tools/autotest/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
import enum

from MAVProxy.modules.lib import mp_util
from MAVProxy.modules.lib import mp_elevation

from pymavlink import mavparm
from pymavlink import mavwp, mavutil, DFReader
Expand Down Expand Up @@ -1542,6 +1543,17 @@ def __init__(self,
self.last_sim_time_cached = 0
self.last_sim_time_cached_wallclock = 0

# to autopilot we do not want to go to the internet for tiles,
# usually. Set this to False to gather tiles from internet in
# the cae there are new tiles required, then add them to the
# repo and set this back to false:
self.terrain_in_offline_mode = True
self.elevationmodel = mp_elevation.ElevationModel(
cachedir=util.reltopdir("Tools/autotest/tilecache/srtm"),
offline=self.terrain_in_offline_mode
)
self.terrain_data_messages_sent = 0 # count of messages back

def __del__(self):
if self.rc_thread is not None:
self.progress("Joining RC thread in __del__")
Expand Down Expand Up @@ -7014,6 +7026,8 @@ def show_test_timings(self):
self.progress(fmt % ("**--tests_total_time--**", tests_total_time))
self.progress("mavproxy_start was called %u times" %
(self.start_mavproxy_count,))
self.progress("Supplied terrain data to autopilot in %u messages" %
(self.terrain_data_messages_sent,))

def send_statustext(self, text):
if sys.version_info.major >= 3 and not isinstance(text, bytes):
Expand Down Expand Up @@ -9490,6 +9504,61 @@ def test_gripper(self):
self.context_pop()
self.reboot_sitl()

def install_terrain_handlers_context(self):
'''install a message handler into the current context which will
listen for an fulfill terrain requests from ArduPilot. Will
die if the data is not available - but
self.terrain_in_offline_mode can be set to true in the
constructor to change this behaviour
'''

def check_terrain_requests(mav, m):
if m.get_type() != 'TERRAIN_REQUEST':
return
self.progress("Processing TERRAIN_REQUEST (%s)" %
self.dump_message_verbose(m))
# swiped from mav_terrain.py
for bit in range(56):
if m.mask & (1 << bit) == 0:
continue

lat = m.lat * 1.0e-7
lon = m.lon * 1.0e-7
bit_spacing = m.grid_spacing * 4
(lat, lon) = mp_util.gps_offset(lat, lon,
east=bit_spacing * (bit % 8),
north=bit_spacing * (bit // 8))
data = []
for i in range(4*4):
y = i % 4
x = i // 4
(lat2, lon2) = mp_util.gps_offset(lat, lon,
east=m.grid_spacing * y,
north=m.grid_spacing * x)
# if we are in online mode then we'll try to fetch
# from the internet into the cache dir:
for i in range(120):
alt = self.elevationmodel.GetElevation(lat2, lon2)
if alt is not None:
break
if self.terrain_in_offline_mode:
break
self.progress("No elevation data for (%f %f); retry" %
(lat2, lon2))
time.sleep(1)
if alt is None:
# no data - we can't send the packet
raise ValueError("No elevation data for (%f %f)" % (lat2, lon2))
data.append(int(alt))
self.terrain_data_messages_sent += 1
self.mav.mav.terrain_data_send(m.lat,
m.lon,
m.grid_spacing,
bit,
data)

self.install_message_hook_context(check_terrain_requests)

def test_set_position_global_int(self, timeout=100):
"""Test set position message in guided mode."""
# Disable heading and yaw test on rover type
Expand All @@ -9503,10 +9572,7 @@ def test_set_position_global_int(self, timeout=100):
test_heading = True
test_yaw_rate = True

# we must start mavproxy here as otherwise we can't get the
# terrain database tiles - this leads to random failures in
# CI!
mavproxy = self.start_mavproxy()
self.install_terrain_handlers_context()

self.set_parameter("FS_GCS_ENABLE", 0)
self.change_mode("GUIDED")
Expand Down Expand Up @@ -9712,8 +9778,6 @@ def send_yaw_rate(rate, target=None):
called_function=lambda plop, empty: send_yaw_rate(
target_rate, None), minimum_duration=5)

self.stop_mavproxy(mavproxy)

self.progress("Getting back to home and disarm")
self.do_RTL(distance_min=0, distance_max=wp_accuracy)
self.disarm_vehicle()
Expand All @@ -9730,10 +9794,7 @@ def test_set_velocity_global_int(self, timeout=30):
test_heading = True
test_yaw_rate = True

# we must start mavproxy here as otherwise we can't get the
# terrain database tiles - this leads to random failures in
# CI!
mavproxy = self.start_mavproxy()
self.install_terrain_handlers_context()

self.set_parameter("FS_GCS_ENABLE", 0)
self.change_mode("GUIDED")
Expand Down Expand Up @@ -10079,8 +10140,6 @@ def send_yaw_rate_vel(rate, vector, mav_frame):
minimum_duration=2
)

self.stop_mavproxy(mavproxy)

self.progress("Getting back to home and disarm")
self.do_RTL(distance_min=0, distance_max=wp_accuracy)
self.disarm_vehicle()
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/pysim/util.py
Original file line number Diff line number Diff line change
Expand Up @@ -556,7 +556,7 @@ def start_MAVProxy_SITL(atype,
aircraft = 'test.%s' % atype
cmd.extend(['--aircraft', aircraft])
cmd.extend(options)
cmd.extend(['--default-modules', 'misc,terrain,wp,rally,fence,param,arm,mode,rc,cmdlong,output'])
cmd.extend(['--default-modules', 'misc,wp,rally,fence,param,arm,mode,rc,cmdlong,output'])

print("PYTHONPATH: %s" % str(env['PYTHONPATH']))
print("Running: %s" % cmd_as_shell(cmd))
Expand Down
11 changes: 3 additions & 8 deletions Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -290,26 +290,21 @@ def fly_mission(self, filename, fence=None, height_accuracy=-1, include_terrain_
self.load_fence(fence)
if self.mavproxy is not None:
self.mavproxy.send('wp list\n')
# terrain can take a *long* time to load:
timeout = 120
if include_terrain_timeout:
timeout *= 1000 # yes, *that* long
mavproxy = self.start_mavproxy()
self.wait_ready_to_arm(timeout=timeout)
self.install_terrain_handlers_context()
self.wait_ready_to_arm()
self.arm_vehicle()
self.change_mode('AUTO')
self.wait_waypoint(1, 19, max_dist=60, timeout=1200)

self.wait_disarmed(timeout=120) # give quadplane a long time to land
# wait for blood sample here
self.set_current_waypoint(20)
self.wait_ready_to_arm(timeout=timeout)
self.wait_ready_to_arm()
self.arm_vehicle()
self.wait_waypoint(20, 34, max_dist=60, timeout=1200)

self.wait_disarmed(timeout=120) # give quadplane a long time to land
self.progress("Mission OK")
self.stop_mavproxy(mavproxy)

def enum_state_name(self, enum_name, state, pretrim=None):
e = mavutil.mavlink.enums[enum_name]
Expand Down
Binary file added Tools/autotest/tilecache/srtm/S28E151.hgt.zip
Binary file not shown.
Binary file added Tools/autotest/tilecache/srtm/S36E149.hgt.zip
Binary file not shown.
Binary file added Tools/autotest/tilecache/srtm/filelist_python
Binary file not shown.