Stephen Dade 5 лет назад
Родитель
Сommit
6341bb9833
7 измененных файлов с 988 добавлено и 2 удалено
  1. 34 2
      README.md
  2. 109 0
      app.py
  3. 184 0
      app_test.py
  4. 299 0
      create_terrain.py
  5. 13 0
      templates/generate.html
  6. 17 0
      templates/index.html
  7. 332 0
      terrain_gen.py

+ 34 - 2
README.md

@@ -1,2 +1,34 @@
-# terraingen
-Ardupilot Terrain Generator website
+# ArduPilot terrain generator
+
+## Summary
+
+This is a website that pre-generates terrain files for Ardupilot. The user enters in the details
+of the area they wish the generate terrain for, then the website will download (if not already cached)
+the raw terrain from ardupilot.org and process it. The user will end up with a terrain.zip that they
+then need to unzip to a "terrain" folder on the SD card in their flight controller.
+
+## For developers
+
+This website uses the flask library.
+
+To install dependencies:
+
+``pip install flask wheel numpy mavproxy crc16 pytest``
+
+To run:
+
+```
+export FLASK_APP=app.py
+flask run
+```
+
+The cached terrain files are stored in ./srtmcache
+
+The unzipped processed files are temporarily stored in ./outputTer-tmp. These are deleted upon the zipping into a single
+downloadable file
+
+The downloadable files are stored in ./outputTer
+
+Each user request is given a UUID, which is incorporated into the folder/filename of the terrain files.
+
+To run the unit tests, type ``pytest``

+ 109 - 0
app.py

@@ -0,0 +1,109 @@
+import uuid
+import threading
+import time
+import queue
+import os
+
+from flask import Flask
+from flask import render_template
+from flask import request
+from flask import json, jsonify
+
+from MAVProxy.modules.mavproxy_map import srtm
+
+from terrain_gen import makeTerrain
+
+# The output folder for all zipped terrain requests
+app = Flask(__name__,static_url_path='/terrain', static_folder='outputTer',)
+
+def clamp(n, smallest, largest):
+    return max(smallest, min(n, largest))
+
+class TerGenThread(threading.Thread):
+    # This is the terrain generator. It will check the queue 
+    # for new requests.
+    def __init__(self):
+        threading.Thread.__init__(self)
+        self.event = threading.Event()
+        # SRTM downloader. Single instance passed to terrain generator
+        self.downloader = srtm.SRTMDownloader(debug=False, cachedir='./srtmcache')
+        self.downloader.loadFileList()
+        self.terStats = {}
+        self.terQ = queue.Queue()
+
+    def addStatus(self, uuidkey, value):
+        self.terStats[uuidkey] = value
+
+    def run(self):
+        print("Starting Terrain Generator")
+        while not self.event.is_set():
+            time.sleep(0.01)
+            if not self.terQ.empty():
+                (radius, lat, lon, spacing, uuidkey, outfolder) = self.terQ.get()
+                print("Starting request: " + str(uuidkey))
+                self.terStats[uuidkey] = "Processing"
+                makeTerrain(self.downloader, radius, lat, lon, spacing, uuidkey, outfolder)
+                del self.terStats[uuidkey]
+        print("Exiting Terrain Generator")
+
+# Terrain generator checker
+x = TerGenThread()
+x.start()
+
+def queueStatus():
+    return len(x.terStats)
+
+def wholeStat():
+    return str(x.terStats)
+
+def shutdown():
+    x.event.set()
+    x.join()
+
+@app.route('/')
+def index():
+    return render_template('index.html')
+
+@app.route('/generate', methods = ['GET', 'POST'])
+def generate():
+    if request.method == 'POST':
+        # parse and sanitise the input
+        try:
+            # request.form['username']
+            lat = float(request.form['lat'])
+            lon = float(request.form['long'])
+            radius = int(request.form['radius'])
+            spacing = int(request.form['spacing'])
+            assert lat < 90
+            assert lon < 180
+            assert lat > -90
+            assert lon > -180
+            radius = clamp(radius, 1, 400)
+            spacing = clamp(spacing, 50, 500)
+        except:
+            print("Bad data")
+            return render_template('generate.html', error = "Error with input")
+
+        # UUID for this terrain generation
+        uuidkey = str(uuid.uuid1())
+
+        # Add this job to the processing queue
+        x.terQ.put((radius, lat, lon, spacing, uuidkey, 'outputTer'))
+        #x.terStats[uuidkey] = "In Queue, pos={0}".format(terQ.qsize())
+        x.addStatus(uuidkey, "In Queue, pos={0}".format(x.terQ.qsize()))
+
+        return render_template('generate.html', urlkey="/terrain/" + uuidkey + ".zip", waittime=x.terQ.qsize()+1, uuidkey=uuidkey)
+    else:
+        print("Bad get")
+        return render_template('generate.html', error = "Need to use POST, not GET")
+
+@app.route('/status/<uuid:uuidkey>')
+def status(uuidkey):
+    if not uuidkey:
+        return jsonify(status = 'Error: incorrect UUID')
+    elif str(uuidkey) in x.terStats:
+        return jsonify(status = 'success', data = str(x.terStats[str(uuidkey)]))
+    elif os.path.exists(os.path.join('.', 'outputTer', str(uuidkey) + ".zip")):
+        return jsonify(status = 'success', data = "ready")
+    else:
+        return jsonify(status = 'Error: bad UUID ' + str(os.path.join('.', 'outputTer', str(uuidkey) + ".zip")))

+ 184 - 0
app_test.py

@@ -0,0 +1,184 @@
+import os
+import time
+
+import pytest
+import uuid
+
+from app import app, queueStatus, shutdown, wholeStat
+
+
+@pytest.fixture
+def client():
+    app.config['TESTING'] = True
+
+    with app.test_client() as client:
+        #with app.app_context():
+        #    app.init_db()
+        yield client
+
+    #shutdown()
+
+def test_homepage(client):
+    """Test that the homepage can be generated"""
+
+    rv = client.get('/')
+    # assert all the controls are there
+    assert b'<title>AP Terrain Generator</title>' in rv.data
+    assert b'<form action="/generate" method="post">' in rv.data
+    assert b'<input type="text" id="lat" name="lat" value="-35.363261">' in rv.data
+    assert b'<input type="text" id="long" name="long" value="149.165230">' in rv.data
+    assert b'<input type="number" id="radius" name="radius" value="100" min="1" max="400">' in rv.data
+    assert b'<input type="number" id="spacing" name="spacing" value="100"  min="50" max="500">' in rv.data
+    assert b'<input type="submit" value="Submit" method="post">' in rv.data
+
+def test_status(client):
+    """Test bad inputs to status page"""
+    uuidkey = str(uuid.uuid1())
+    rc = client.get('/status/' + uuidkey, follow_redirects=True)
+    assert b'Error: bad UUID' in rc.data
+
+    rc = client.get('/status/', follow_redirects=True)
+    assert b'404 Not Found' in rc.data
+
+    rc = client.get('/status/notauuid123' + uuidkey, follow_redirects=True)
+    assert b'404 Not Found' in rc.data
+
+def test_badinput(client):
+    """Test bad inputs"""
+    # no input
+    rv = client.post('/generate', data=dict(
+    ), follow_redirects=True)
+
+    assert b'<title>AP Terrain Generator</title>' in rv.data
+    assert b'Error' in rv.data
+    assert b'Link To Download' not in rv.data
+
+    #partial input
+    rv = client.post('/generate', data=dict(
+        lat='-35.363261',
+        long='149.165230',
+    ), follow_redirects=True)
+
+    assert b'<title>AP Terrain Generator</title>' in rv.data
+    assert b'Error' in rv.data
+    assert b'Link To Download' not in rv.data
+
+    #bad lon/lat
+    rv = client.post('/generate', data=dict(
+        lat='I am bad data',
+        long='echo test',
+        radius='1',
+        spacing='100'
+    ), follow_redirects=True)
+
+    assert b'<title>AP Terrain Generator</title>' in rv.data
+    assert b'Error' in rv.data
+    assert b'Link To Download' not in rv.data
+
+    #out of bounds lon/lat
+    rv = client.post('/generate', data=dict(
+        lat='206.56',
+        long='-400',
+        radius='1',
+        spacing='100'
+    ), follow_redirects=True)
+
+    assert b'<title>AP Terrain Generator</title>' in rv.data
+    assert b'Error' in rv.data
+    assert b'Link To Download' not in rv.data
+
+def test_simplegen(client):
+    """Test that a small piece of terrain can be generated"""
+
+    rv = client.post('/generate', data=dict(
+        lat='-35.363261',
+        long='149.165230',
+        radius='1',
+        spacing='200'
+    ), follow_redirects=True)
+
+    assert b'<title>AP Terrain Generator</title>' in rv.data
+    assert b'Error' not in rv.data
+    assert b'Link To Download' in rv.data
+
+    uuidkey = (rv.data.split(b"footer")[1][1:-2]).decode("utf-8") 
+    assert uuidkey != ""
+
+    #wait for generator to complete, up to 30 seconds
+    startime = time.time()
+    while True:
+        time.sleep(0.5)
+        if time.time() - startime > 30:
+            assert False
+            break
+        else:
+            rc = client.get('/status/' + uuidkey, follow_redirects=True)
+            if "ready" in rc.data.decode("utf-8") :
+                break
+
+    #file should be ready for download and around 2MB in size
+    rdown = client.get('/terrain/' + uuidkey + ".zip", follow_redirects=True)
+    assert len(rdown.data) > (1*1024*1024)
+
+    #shutdown()
+
+def test_multigen(client):
+    """Test that a a few small piece of terrains can be generated"""
+
+    rva = client.post('/generate', data=dict(
+        lat='-35.363261',
+        long='149.165230',
+        radius='1',
+        spacing='200'
+    ), follow_redirects=True)
+    time.sleep(0.1)
+
+    rvb = client.post('/generate', data=dict(
+        lat='-35.363261',
+        long='147.165230',
+        radius='1',
+        spacing='200'
+    ), follow_redirects=True)
+    time.sleep(0.1)
+
+    rvc = client.post('/generate', data=dict(
+        lat='-30.363261',
+        long='137.165230',
+        radius='1',
+        spacing='200'
+    ), follow_redirects=True)
+    time.sleep(0.1)
+
+    # Assert reponse is OK and get UUID for each ter gen
+    allUuid = []
+    for rv in [rva, rvb, rvc]:
+        assert b'<title>AP Terrain Generator</title>' in rv.data
+        assert b'Error' not in rv.data
+        assert b'Link To Download' in rv.data
+        uuidkey = (rv.data.split(b"footer")[1][1:-2]).decode("utf-8") 
+        assert uuidkey != ""
+        allUuid.append(uuidkey)
+
+    #wait for generator to complete, up to 50 seconds
+    startime = time.time()
+    allUuidComplete = []
+    while len(allUuid) != len(allUuidComplete):
+        time.sleep(1)
+        if time.time() - startime > 50:
+            break
+        else:
+            # check if done
+            for uukey in allUuid:
+                rcc = client.get('/status/' + uukey, follow_redirects=True)
+                if "ready" in rcc.data.decode("utf-8") and (uukey not in allUuidComplete):
+                    allUuidComplete.append(uukey)
+
+    #files should be ready for download and around 2MB in size
+    for uukey in allUuid:
+        rdown = client.get('/terrain/' + uukey + ".zip", follow_redirects=True)
+        assert len(rdown.data) > (0.7*1024*1024)
+
+    print(wholeStat())
+    shutdown()
+
+

+ 299 - 0
create_terrain.py

@@ -0,0 +1,299 @@
+#!/usr/bin/env python
+'''
+create ardupilot terrain database files
+'''
+
+from MAVProxy.modules.mavproxy_map import srtm
+import math, struct, os, sys
+import crc16, time, struct
+
+# MAVLink sends 4x4 grids
+TERRAIN_GRID_MAVLINK_SIZE = 4
+
+# a 2k grid_block on disk contains 8x7 of the mavlink grids.  Each
+# grid block overlaps by one with its neighbour. This ensures that
+# the altitude at any point can be calculated from a single grid
+# block
+TERRAIN_GRID_BLOCK_MUL_X = 7
+TERRAIN_GRID_BLOCK_MUL_Y = 8
+
+# this is the spacing between 32x28 grid blocks, in grid_spacing units
+TERRAIN_GRID_BLOCK_SPACING_X = ((TERRAIN_GRID_BLOCK_MUL_X-1)*TERRAIN_GRID_MAVLINK_SIZE)
+TERRAIN_GRID_BLOCK_SPACING_Y = ((TERRAIN_GRID_BLOCK_MUL_Y-1)*TERRAIN_GRID_MAVLINK_SIZE)
+
+# giving a total grid size of a disk grid_block of 32x28
+TERRAIN_GRID_BLOCK_SIZE_X = (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_X)
+TERRAIN_GRID_BLOCK_SIZE_Y = (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_Y)
+
+# format of grid on disk
+TERRAIN_GRID_FORMAT_VERSION = 1
+
+IO_BLOCK_SIZE = 2048
+
+GRID_SPACING = 100
+
+def to_float32(f):
+    '''emulate single precision float'''
+    return struct.unpack('f', struct.pack('f',f))[0]
+
+LOCATION_SCALING_FACTOR = to_float32(0.011131884502145034)
+LOCATION_SCALING_FACTOR_INV = to_float32(89.83204953368922)
+
+def longitude_scale(lat):
+    '''get longitude scale factor'''
+    scale = to_float32(math.cos(to_float32(math.radians(lat))))
+    return max(scale, 0.01)
+
+def get_distance_NE_e7(lat1, lon1, lat2, lon2):
+    '''get distance tuple between two positions in 1e7 format'''
+    return ((lat2 - lat1) * LOCATION_SCALING_FACTOR, (lon2 - lon1) * LOCATION_SCALING_FACTOR * longitude_scale(lat1*1.0e-7))
+
+def add_offset(lat_e7, lon_e7, ofs_north, ofs_east):
+    '''add offset in meters to a position'''
+    dlat = int(float(ofs_north) * LOCATION_SCALING_FACTOR_INV)
+    dlng = int((float(ofs_east) * LOCATION_SCALING_FACTOR_INV) / longitude_scale(lat_e7*1.0e-7))
+    return (int(lat_e7+dlat), int(lon_e7+dlng))
+
+def east_blocks(lat_e7, lon_e7):
+    '''work out how many blocks per stride on disk'''
+    lat2_e7 = lat_e7
+    lon2_e7 = lon_e7 + 10*1000*1000
+
+    # shift another two blocks east to ensure room is available
+    lat2_e7, lon2_e7 = add_offset(lat2_e7, lon2_e7, 0, 2*GRID_SPACING*TERRAIN_GRID_BLOCK_SIZE_Y)
+    offset = get_distance_NE_e7(lat_e7, lon_e7, lat2_e7, lon2_e7)
+    return int(offset[1] / (GRID_SPACING*TERRAIN_GRID_BLOCK_SPACING_Y))
+
+def pos_from_file_offset(lat_degrees, lon_degrees, file_offset):
+    '''return a lat/lon in 1e7 format given a file offset'''
+
+    ref_lat = int(lat_degrees*10*1000*1000)
+    ref_lon = int(lon_degrees*10*1000*1000)
+
+    stride = east_blocks(ref_lat, ref_lon)
+    blocks = file_offset // IO_BLOCK_SIZE
+    grid_idx_x = blocks // stride
+    grid_idx_y = blocks % stride
+
+    idx_x = grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X
+    idx_y = grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y
+    offset = (idx_x * GRID_SPACING, idx_y * GRID_SPACING)
+
+    (lat_e7, lon_e7) = add_offset(ref_lat, ref_lon, offset[0], offset[1])
+
+    offset = get_distance_NE_e7(ref_lat, ref_lon, lat_e7, lon_e7)
+    grid_idx_x = int(idx_x / TERRAIN_GRID_BLOCK_SPACING_X)
+    grid_idx_y = int(idx_y / TERRAIN_GRID_BLOCK_SPACING_Y)
+
+    (lat_e7, lon_e7) = add_offset(ref_lat, ref_lon,
+                                  grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X * float(GRID_SPACING),
+                                  grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y * float(GRID_SPACING))
+
+    return (lat_e7, lon_e7)
+            
+class GridBlock(object):
+    def __init__(self, lat_int, lon_int, lat, lon):
+        '''
+        a grid block is a structure in a local file containing height
+        information. Each grid block is 2048 bytes in size, to keep file IO to
+        block oriented SD cards efficient
+        '''
+
+        # crc of whole block, taken with crc=0
+        self.crc = 0
+
+        # format version number
+        self.version = TERRAIN_GRID_FORMAT_VERSION
+
+        # grid spacing in meters
+        self.spacing = GRID_SPACING
+
+        # heights in meters over a 32*28 grid
+        self.height = []
+        for x in range(TERRAIN_GRID_BLOCK_SIZE_X):
+            self.height.append([0]*TERRAIN_GRID_BLOCK_SIZE_Y)
+
+        # bitmap of 4x4 grids filled in from GCS (56 bits are used)
+        self.bitmap = (1<<56)-1
+
+        lat_e7 = int(lat * 1.0e7)
+        lon_e7 = int(lon * 1.0e7)
+
+        # grids start on integer degrees. This makes storing terrain data on
+        # the SD card a bit easier. Note that this relies on the python floor
+        # behaviour with integer division
+        self.lat_degrees = lat_int
+        self.lon_degrees = lon_int
+
+        # create reference position for this rounded degree position
+        ref_lat = self.lat_degrees*10*1000*1000
+        ref_lon = self.lon_degrees*10*1000*1000
+
+        # find offset from reference
+        offset = get_distance_NE_e7(ref_lat, ref_lon, lat_e7, lon_e7)
+
+        offset = (round(offset[0]), round(offset[1]))
+
+        # get indices in terms of grid_spacing elements
+        idx_x = int(offset[0] / GRID_SPACING)
+        idx_y = int(offset[1] / GRID_SPACING)
+
+        # find indexes into 32*28 grids for this degree reference. Note
+        # the use of TERRAIN_GRID_BLOCK_SPACING_{X,Y} which gives a one square
+        # overlap between grids
+        self.grid_idx_x = idx_x // TERRAIN_GRID_BLOCK_SPACING_X
+        self.grid_idx_y = idx_y // TERRAIN_GRID_BLOCK_SPACING_Y
+
+        # calculate lat/lon of SW corner of 32*28 grid_block
+        (ref_lat, ref_lon) = add_offset(ref_lat, ref_lon,
+                                        self.grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X * float(GRID_SPACING),
+                                        self.grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y * float(GRID_SPACING))
+        self.lat = ref_lat
+        self.lon = ref_lon
+
+    def fill(self, gx, gy, altitude):
+        '''fill a square'''
+        self.height[gx][gy] = int(altitude)
+
+    def blocknum(self):
+        '''find IO block number'''
+        stride = east_blocks(self.lat_degrees*1e7, self.lon_degrees*1e7)
+        return stride * self.grid_idx_x + self.grid_idx_y
+
+class DataFile(object):
+    def __init__(self, lat, lon):
+        if lat < 0:
+            NS = 'S'
+        else:
+            NS = 'N'
+        if lon < 0:
+            EW = 'W'
+        else:
+            EW = 'E'
+        name = "terrain/%c%02u%c%03u.DAT" % (NS, min(abs(int(lat)), 99),
+                                        EW, min(abs(int(lon)), 999))
+        try:
+            os.mkdir("terrain")
+        except Exception:
+            pass
+        if not os.path.exists(name):
+            self.fh = open(name, 'w+b')
+        else:
+            self.fh = open(name, 'r+b')
+
+    def seek_offset(self, block):
+        '''seek to right offset'''
+        # work out how many longitude blocks there are at this latitude
+        file_offset = block.blocknum() * IO_BLOCK_SIZE
+        self.fh.seek(file_offset)
+
+    def pack(self, block):
+        '''pack into a block'''
+        buf = bytes()
+        buf += struct.pack("<QiiHHH", block.bitmap, block.lat, block.lon, block.crc, block.version, block.spacing)
+        for gx in range(TERRAIN_GRID_BLOCK_SIZE_X):
+            buf += struct.pack("<%uh" % TERRAIN_GRID_BLOCK_SIZE_Y, *block.height[gx])
+        buf += struct.pack("<HHhb", block.grid_idx_x, block.grid_idx_y, block.lon_degrees, block.lat_degrees)
+        return buf
+
+    def write(self, block):
+        '''write a grid block'''
+        self.seek_offset(block)
+        block.crc = 0
+        buf = self.pack(block)
+        block.crc = crc16.crc16xmodem(buf)
+        buf = self.pack(block)
+        self.fh.write(buf)
+
+    def check_filled(self, block):
+        '''read a grid block and check if already filled'''
+        self.seek_offset(block)
+        buf = self.fh.read(IO_BLOCK_SIZE)
+        if len(buf) != IO_BLOCK_SIZE:
+            return False
+        (bitmap, lat, lon, crc, version, spacing) = struct.unpack("<QiiHHH", buf[:22])
+        if (version != TERRAIN_GRID_FORMAT_VERSION or
+            abs(lat - block.lat)>2 or
+            abs(lon - block.lon)>2 or
+            spacing != GRID_SPACING or
+            bitmap != (1<<56)-1):
+            return False
+        buf = buf[:16] + struct.pack("<H", 0) + buf[18:]
+        crc2 = crc16.crc16xmodem(buf[:1821])
+        if crc2 != crc:
+            return False
+        return True
+
+def create_degree(lat, lon):
+    '''create data file for one degree lat/lon'''
+    lat_int = int(math.floor(lat))
+    lon_int = int(math.floor((lon)))
+
+    tiles = {}
+
+    dfile = DataFile(lat_int, lon_int)
+
+    print("Creating for %d %d" % (lat_int, lon_int))
+
+    total_blocks = east_blocks(lat_int*1e7, lon_int*1e7) * TERRAIN_GRID_BLOCK_SIZE_Y
+
+    for blocknum in range(total_blocks):
+        (lat_e7, lon_e7) = pos_from_file_offset(lat_int, lon_int, blocknum * IO_BLOCK_SIZE)
+        lat = lat_e7 * 1.0e-7
+        lon = lon_e7 * 1.0e-7
+        grid = GridBlock(lat_int, lon_int, lat, lon)
+        if grid.blocknum() != blocknum:
+            continue
+        if not args.force and dfile.check_filled(grid):
+            continue
+        for gx in range(TERRAIN_GRID_BLOCK_SIZE_X):
+            for gy in range(TERRAIN_GRID_BLOCK_SIZE_Y):
+                lat_e7, lon_e7 = add_offset(lat*1.0e7, lon*1.0e7, gx*GRID_SPACING, gy*GRID_SPACING)
+                lat2_int = int(math.floor(lat_e7*1.0e-7))
+                lon2_int = int(math.floor(lon_e7*1.0e-7))
+                tile_idx = (lat2_int, lon2_int)
+                while not tile_idx in tiles:
+                    tile = downloader.getTile(lat2_int, lon2_int)
+                    waited = False
+                    if tile == 0:
+                        print("waiting on download of %d,%d" % (lat2_int, lon2_int))
+                        time.sleep(0.3)
+                        waited = True
+                        continue
+                    if waited:
+                        print("downloaded %d,%d" % (lat2_int, lon2_int))
+                    tiles[tile_idx] = tile
+                altitude = tiles[tile_idx].getAltitudeFromLatLon(lat_e7*1.0e-7, lon_e7*1.0e-7)
+                grid.fill(gx, gy, altitude)
+        dfile.write(grid)
+
+from argparse import ArgumentParser
+parser = ArgumentParser(description='terrain data creator')
+
+parser.add_argument("lat", type=float, default=-35.363261)
+parser.add_argument("lon", type=float, default=149.165230)
+parser.add_argument("--force", action='store_true', help="overwrite existing full blocks")
+parser.add_argument("--radius", type=int, default=100, help="radius in km")
+parser.add_argument("--debug", action='store_true', default=False)
+parser.add_argument("--spacing", type=int, default=100, help="grid spacing in meters")
+args = parser.parse_args()
+
+downloader = srtm.SRTMDownloader(debug=args.debug)
+downloader.loadFileList()
+
+GRID_SPACING = args.spacing
+
+done = set()
+
+for dx in range(-args.radius, args.radius):
+    for dy in range(-args.radius, args.radius):
+        (lat2,lon2) = add_offset(args.lat*1e7, args.lon*1e7, dx*1000.0, dy*1000.0)
+        lat_int = int(round(lat2 * 1.0e-7))
+        lon_int = int(round(lon2 * 1.0e-7))
+        tag = (lat_int, lon_int)
+        if tag in done:
+            continue
+        done.add(tag)
+        create_degree(lat_int, lon_int)
+
+create_degree(args.lat, args.lon)

+ 13 - 0
templates/generate.html

@@ -0,0 +1,13 @@
+<!doctype html>
+<title>AP Terrain Generator</title>
+<h1>AP Terrain Generator</h1>
+<p>File is being processed. This may take up to {{ waittime }} minutes.</p>
+
+{% if error %}
+  <p>Error: {{ error }}!</p>
+{% else %}
+  <p>When finished, you can download from: <a href="{{ urlkey }}" download="terrain.zip">Link To Download</a></p>
+  <p>This should be unzipped to the autopilot's SD card, within in the "terrain" folder.</p>
+{% endif %}
+
+<footer>{{uuidkey}}</footer>

+ 17 - 0
templates/index.html

@@ -0,0 +1,17 @@
+<!doctype html>
+<title>AP Terrain Generator</title>
+<h1>AP Terrain Generator</h1>
+<p>Use this to generate terrain to put on your SD card</p>
+<h2>Options</h2>
+ <form action="/generate" method="post">
+  <label for="lat">Latitude:</label><br>
+  <input type="text" id="lat" name="lat" value="-35.363261"><br>
+  <label for="long">Longitude:</label><br>
+  <input type="text" id="long" name="long" value="149.165230"><br>
+  <label for="radius">Radius (km):</label><br>
+  <input type="number" id="radius" name="radius" value="100" min="1" max="400"><br>
+  <label for="spacing">Grid Spacing (m):</label><br>
+  <input type="number" id="spacing" name="spacing" value="100"  min="50" max="500"><br>
+  <br>
+  <input type="submit" value="Submit" method="post">
+ </form> 

+ 332 - 0
terrain_gen.py

@@ -0,0 +1,332 @@
+#!/usr/bin/env python
+'''
+create ardupilot terrain database files
+'''
+
+import math, struct, os, sys, shutil
+import crc16, time, struct, zipfile
+
+# MAVLink sends 4x4 grids
+TERRAIN_GRID_MAVLINK_SIZE = 4
+
+# a 2k grid_block on disk contains 8x7 of the mavlink grids.  Each
+# grid block overlaps by one with its neighbour. This ensures that
+# the altitude at any point can be calculated from a single grid
+# block
+TERRAIN_GRID_BLOCK_MUL_X = 7
+TERRAIN_GRID_BLOCK_MUL_Y = 8
+
+# this is the spacing between 32x28 grid blocks, in grid_spacing units
+TERRAIN_GRID_BLOCK_SPACING_X = ((TERRAIN_GRID_BLOCK_MUL_X-1)*TERRAIN_GRID_MAVLINK_SIZE)
+TERRAIN_GRID_BLOCK_SPACING_Y = ((TERRAIN_GRID_BLOCK_MUL_Y-1)*TERRAIN_GRID_MAVLINK_SIZE)
+
+# giving a total grid size of a disk grid_block of 32x28
+TERRAIN_GRID_BLOCK_SIZE_X = (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_X)
+TERRAIN_GRID_BLOCK_SIZE_Y = (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_Y)
+
+# format of grid on disk
+TERRAIN_GRID_FORMAT_VERSION = 1
+
+IO_BLOCK_SIZE = 2048
+
+#GRID_SPACING = 100
+
+def to_float32(f):
+    '''emulate single precision float'''
+    return struct.unpack('f', struct.pack('f',f))[0]
+
+LOCATION_SCALING_FACTOR = to_float32(0.011131884502145034)
+LOCATION_SCALING_FACTOR_INV = to_float32(89.83204953368922)
+
+def longitude_scale(lat):
+    '''get longitude scale factor'''
+    scale = to_float32(math.cos(to_float32(math.radians(lat))))
+    return max(scale, 0.01)
+
+def get_distance_NE_e7(lat1, lon1, lat2, lon2):
+    '''get distance tuple between two positions in 1e7 format'''
+    return ((lat2 - lat1) * LOCATION_SCALING_FACTOR, (lon2 - lon1) * LOCATION_SCALING_FACTOR * longitude_scale(lat1*1.0e-7))
+
+def add_offset(lat_e7, lon_e7, ofs_north, ofs_east):
+    '''add offset in meters to a position'''
+    dlat = int(float(ofs_north) * LOCATION_SCALING_FACTOR_INV)
+    dlng = int((float(ofs_east) * LOCATION_SCALING_FACTOR_INV) / longitude_scale(lat_e7*1.0e-7))
+    return (int(lat_e7+dlat), int(lon_e7+dlng))
+
+def east_blocks(lat_e7, lon_e7, grid_spacing):
+    '''work out how many blocks per stride on disk'''
+    lat2_e7 = lat_e7
+    lon2_e7 = lon_e7 + 10*1000*1000
+
+    # shift another two blocks east to ensure room is available
+    lat2_e7, lon2_e7 = add_offset(lat2_e7, lon2_e7, 0, 2*grid_spacing*TERRAIN_GRID_BLOCK_SIZE_Y)
+    offset = get_distance_NE_e7(lat_e7, lon_e7, lat2_e7, lon2_e7)
+    return int(offset[1] / (grid_spacing*TERRAIN_GRID_BLOCK_SPACING_Y))
+
+def pos_from_file_offset(lat_degrees, lon_degrees, file_offset, grid_spacing):
+    '''return a lat/lon in 1e7 format given a file offset'''
+
+    ref_lat = int(lat_degrees*10*1000*1000)
+    ref_lon = int(lon_degrees*10*1000*1000)
+
+    stride = east_blocks(ref_lat, ref_lon, grid_spacing)
+    blocks = file_offset // IO_BLOCK_SIZE
+    grid_idx_x = blocks // stride
+    grid_idx_y = blocks % stride
+
+    idx_x = grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X
+    idx_y = grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y
+    offset = (idx_x * grid_spacing, idx_y * grid_spacing)
+
+    (lat_e7, lon_e7) = add_offset(ref_lat, ref_lon, offset[0], offset[1])
+
+    offset = get_distance_NE_e7(ref_lat, ref_lon, lat_e7, lon_e7)
+    grid_idx_x = int(idx_x / TERRAIN_GRID_BLOCK_SPACING_X)
+    grid_idx_y = int(idx_y / TERRAIN_GRID_BLOCK_SPACING_Y)
+
+    (lat_e7, lon_e7) = add_offset(ref_lat, ref_lon,
+                                  grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X * float(grid_spacing),
+                                  grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y * float(grid_spacing))
+
+    return (lat_e7, lon_e7)
+            
+class GridBlock(object):
+    def __init__(self, lat_int, lon_int, lat, lon, grid_spacing):
+        '''
+        a grid block is a structure in a local file containing height
+        information. Each grid block is 2048 bytes in size, to keep file IO to
+        block oriented SD cards efficient
+        '''
+
+        # crc of whole block, taken with crc=0
+        self.crc = 0
+
+        # format version number
+        self.version = TERRAIN_GRID_FORMAT_VERSION
+
+        # grid spacing in meters
+        self.spacing = grid_spacing
+
+        # heights in meters over a 32*28 grid
+        self.height = []
+        for x in range(TERRAIN_GRID_BLOCK_SIZE_X):
+            self.height.append([0]*TERRAIN_GRID_BLOCK_SIZE_Y)
+
+        # bitmap of 4x4 grids filled in from GCS (56 bits are used)
+        self.bitmap = (1<<56)-1
+
+        lat_e7 = int(lat * 1.0e7)
+        lon_e7 = int(lon * 1.0e7)
+
+        # grids start on integer degrees. This makes storing terrain data on
+        # the SD card a bit easier. Note that this relies on the python floor
+        # behaviour with integer division
+        self.lat_degrees = lat_int
+        self.lon_degrees = lon_int
+
+        # create reference position for this rounded degree position
+        ref_lat = self.lat_degrees*10*1000*1000
+        ref_lon = self.lon_degrees*10*1000*1000
+
+        # find offset from reference
+        offset = get_distance_NE_e7(ref_lat, ref_lon, lat_e7, lon_e7)
+
+        offset = (round(offset[0]), round(offset[1]))
+
+        # get indices in terms of grid_spacing elements
+        idx_x = int(offset[0] / self.spacing)
+        idx_y = int(offset[1] / self.spacing)
+
+        # find indexes into 32*28 grids for this degree reference. Note
+        # the use of TERRAIN_GRID_BLOCK_SPACING_{X,Y} which gives a one square
+        # overlap between grids
+        self.grid_idx_x = idx_x // TERRAIN_GRID_BLOCK_SPACING_X
+        self.grid_idx_y = idx_y // TERRAIN_GRID_BLOCK_SPACING_Y
+
+        # calculate lat/lon of SW corner of 32*28 grid_block
+        (ref_lat, ref_lon) = add_offset(ref_lat, ref_lon,
+                                        self.grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X * float(self.spacing),
+                                        self.grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y * float(self.spacing))
+        self.lat = ref_lat
+        self.lon = ref_lon
+
+    def fill(self, gx, gy, altitude):
+        '''fill a square'''
+        self.height[gx][gy] = int(altitude)
+
+    def blocknum(self):
+        '''find IO block number'''
+        stride = east_blocks(self.lat_degrees*1e7, self.lon_degrees*1e7, self.spacing)
+        return stride * self.grid_idx_x + self.grid_idx_y
+
+class DataFile(object):
+    def __init__(self, lat, lon, folder):
+        if lat < 0:
+            NS = 'S'
+        else:
+            NS = 'N'
+        if lon < 0:
+            EW = 'W'
+        else:
+            EW = 'E'
+        name = folder + "/%c%02u%c%03u.DAT" % (NS, min(abs(int(lat)), 99),
+                                        EW, min(abs(int(lon)), 999))
+        try:
+            os.mkdir(folder)
+        except Exception:
+            pass
+        if not os.path.exists(name):
+            self.fh = open(name, 'w+b')
+        else:
+            self.fh = open(name, 'r+b')
+
+    def seek_offset(self, block):
+        '''seek to right offset'''
+        # work out how many longitude blocks there are at this latitude
+        file_offset = block.blocknum() * IO_BLOCK_SIZE
+        self.fh.seek(file_offset)
+
+    def pack(self, block):
+        '''pack into a block'''
+        buf = bytes()
+        buf += struct.pack("<QiiHHH", block.bitmap, block.lat, block.lon, block.crc, block.version, block.spacing)
+        for gx in range(TERRAIN_GRID_BLOCK_SIZE_X):
+            buf += struct.pack("<%uh" % TERRAIN_GRID_BLOCK_SIZE_Y, *block.height[gx])
+        buf += struct.pack("<HHhb", block.grid_idx_x, block.grid_idx_y, block.lon_degrees, block.lat_degrees)
+        return buf
+
+    def write(self, block):
+        '''write a grid block'''
+        self.seek_offset(block)
+        block.crc = 0
+        buf = self.pack(block)
+        block.crc = crc16.crc16xmodem(buf)
+        buf = self.pack(block)
+        self.fh.write(buf)
+
+    def check_filled(self, block, grid_spacing):
+        '''read a grid block and check if already filled'''
+        self.seek_offset(block)
+        buf = self.fh.read(IO_BLOCK_SIZE)
+        if len(buf) != IO_BLOCK_SIZE:
+            return False
+        (bitmap, lat, lon, crc, version, spacing) = struct.unpack("<QiiHHH", buf[:22])
+        if (version != TERRAIN_GRID_FORMAT_VERSION or
+            abs(lat - block.lat)>2 or
+            abs(lon - block.lon)>2 or
+            spacing != grid_spacing or
+            bitmap != (1<<56)-1):
+            return False
+        buf = buf[:16] + struct.pack("<H", 0) + buf[18:]
+        crc2 = crc16.crc16xmodem(buf[:1821])
+        if crc2 != crc:
+            return False
+        return True
+
+def create_degree(downloader, lat, lon, folder, grid_spacing):
+    '''create data file for one degree lat/lon'''
+    lat_int = int(math.floor(lat))
+    lon_int = int(math.floor((lon)))
+
+    tiles = {}
+
+    dfile = DataFile(lat_int, lon_int, folder)
+
+    print("Creating for %d %d" % (lat_int, lon_int))
+
+    total_blocks = east_blocks(lat_int*1e7, lon_int*1e7, grid_spacing) * TERRAIN_GRID_BLOCK_SIZE_Y
+
+    for blocknum in range(total_blocks):
+        (lat_e7, lon_e7) = pos_from_file_offset(lat_int, lon_int, blocknum * IO_BLOCK_SIZE, grid_spacing)
+        lat = lat_e7 * 1.0e-7
+        lon = lon_e7 * 1.0e-7
+        grid = GridBlock(lat_int, lon_int, lat, lon, grid_spacing)
+        if grid.blocknum() != blocknum:
+            continue
+        if dfile.check_filled(grid, grid_spacing):
+            continue
+        for gx in range(TERRAIN_GRID_BLOCK_SIZE_X):
+            for gy in range(TERRAIN_GRID_BLOCK_SIZE_Y):
+                lat_e7, lon_e7 = add_offset(lat*1.0e7, lon*1.0e7, gx*grid_spacing, gy*grid_spacing)
+                lat2_int = int(math.floor(lat_e7*1.0e-7))
+                lon2_int = int(math.floor(lon_e7*1.0e-7))
+                tile_idx = (lat2_int, lon2_int)
+                while not tile_idx in tiles:
+                    tile = downloader.getTile(lat2_int, lon2_int)
+                    waited = False
+                    if tile == 0:
+                        print("waiting on download of %d,%d" % (lat2_int, lon2_int))
+                        time.sleep(0.3)
+                        waited = True
+                        continue
+                    if waited:
+                        print("downloaded %d,%d" % (lat2_int, lon2_int))
+                    tiles[tile_idx] = tile
+                altitude = tiles[tile_idx].getAltitudeFromLatLon(lat_e7*1.0e-7, lon_e7*1.0e-7)
+                grid.fill(gx, gy, altitude)
+        dfile.write(grid)
+
+def makeTerrain(downloader, radius, lat, lon, spacing, uuid, folder):
+    #GRID_SPACING = spacing
+
+    done = set()
+
+    #create folder if required
+    try:
+        # Create target Directory
+        os.mkdir(os.path.join(os.getcwd(), folder))
+    except FileExistsError:
+        pass
+
+    try:
+        os.mkdir(os.path.join(os.getcwd(), folder + "-tmp"))
+    except FileExistsError:
+        pass
+
+    folderthis = os.path.join(os.getcwd(), folder + "-tmp", uuid)
+    zipthis = os.path.join(os.getcwd(), folder, uuid + '.zip')
+
+    print("Doing " + folderthis + " -> " + zipthis)
+
+    # progress tracking. Extra 10% is for zip compression at the end
+    #numtotal = (len(range(-radius, radius))**2)*1.1
+    #print(numtotal)
+    #numpercent = 0
+
+    for dx in range(-radius, radius):
+        for dy in range(-radius, radius):
+            (lat2,lon2) = add_offset(lat*1e7, lon*1e7, dx*1000.0, dy*1000.0)
+            lat_int = int(round(lat2 * 1.0e-7))
+            lon_int = int(round(lon2 * 1.0e-7))
+            tag = (lat_int, lon_int)
+            if tag in done:
+                #numpercent += 1
+                continue
+            done.add(tag)
+            #print("At {0:.2f}%".format(numpercent*100/numtotal))
+            create_degree(downloader, lat_int, lon_int, folderthis, spacing)
+            #numpercent += 1
+
+    #print("At Final {0:.2f}%".format(numpercent*100/numtotal))
+    create_degree(downloader, lat, lon, folderthis, spacing)
+    #numpercent += 1
+
+    # compress
+    terrain_zip = zipfile.ZipFile(zipthis, 'w')
+    
+     
+    print("At Compress ")
+    #numpercent  = numpercent * 1.1
+    for folder, subfolders, files in os.walk(folderthis):
+        for file in files:
+            terrain_zip.write(os.path.join(folder, file), file, compress_type = zipfile.ZIP_DEFLATED)
+     
+    terrain_zip.close()
+
+    #remove old folder
+    try:
+        shutil.rmtree(folderthis)
+    except OSError as e:
+        print("Error: %s : %s" % (folderthis, e.strerror))
+
+    print("At Done")