فهرست منبع

Updated tile generation

Stephen Dade 5 سال پیش
والد
کامیت
afbabec2f9
2فایلهای تغییر یافته به همراه53 افزوده شده و 50 حذف شده
  1. 43 11
      offline_check.py
  2. 10 39
      terrain_gen.py

+ 43 - 11
offline_check.py

@@ -23,7 +23,10 @@ def check_filled(block, lat_int, lon_int, grid_spacing):
         print("Bad size {0} of {1}".format(len(block), IO_BLOCK_SIZE))
         return False
     (bitmap, lat, lon, crc, version, spacing) = struct.unpack("<QiiHHH", block[:22])
-    if (version != TERRAIN_GRID_FORMAT_VERSION):
+    if(lat == 0 and lon == 0 and crc == 0 and version == 0 and spacing == 0):
+        #print("Empty block")
+        return True
+    if (str(version) != str(TERRAIN_GRID_FORMAT_VERSION)):
         print("Bad version: " + str(version))
         return False
     if abs(lat_int - (lat/1E7)) > 2 or abs(lon_int - (lon/1E7)) > 2:
@@ -41,7 +44,9 @@ def check_filled(block, lat_int, lon_int, grid_spacing):
     if crc2 != crc:
         print("Bad CRC")
         return False
-    return True
+
+    # all is good, return lon/lat of block
+    return (lat, lon)
 
 if __name__ == '__main__':
     # Create the parser
@@ -63,6 +68,7 @@ if __name__ == '__main__':
         if file.endswith("DAT.gz") or file.endswith("DAT"):
             # It's a compressed tile
             # 1. Check it's a valid gzip
+            print(file)
             tile = None
             try:
                 lat_int = int(os.path.basename(file)[1:3])
@@ -82,17 +88,43 @@ if __name__ == '__main__':
                 print(e)
             # 2. Is it a valid dat file?
             if (tile):
-                total_blocks = east_blocks(lat_int*1e7, lon_int*1e7, grid_spacing) * TERRAIN_GRID_BLOCK_SIZE_Y
-                # 2a. Are the correct number of blocks present?
-                # There is an extra 1821 bytes at the end on the file (2048-1821 = 227), as the 
+                
+                # 2a. Are the correct number (integer) of blocks present?
+                # It will be a multiple of 2048 bytes (block size)
+                # There is an missing 227 bytes at the end on the file (2048-1821 = 227), as the 
                 # terrain blocks only take up 1821 bytes.
-                if (len(tile)+227) != (total_blocks * IO_BLOCK_SIZE):
-                    print("Bad number of blocks: {0}, {1} vs {2}".format(file, len(tile), total_blocks * IO_BLOCK_SIZE))
+                # APM actually adds the padding on the end, so extra 227 is not needed sometimes
+                total_blocks = 0
+                if (len(tile)+227) % IO_BLOCK_SIZE == 0:
+                    total_blocks = int((len(tile)+227) / IO_BLOCK_SIZE)
+                elif len(tile) % IO_BLOCK_SIZE == 0:
+                    total_blocks = int(len(tile) / IO_BLOCK_SIZE)
+                else:
+                    print("Bad file size: {0}. {1} extra bytes at end".format(file, len(tile), len(tile) % IO_BLOCK_SIZE))
+                print("Has {0} blocks".format(total_blocks))
                 # 2b. Does each block have the correct CRC and fields?
-                for blocknum in range(total_blocks):
-                    block = tile[(blocknum * IO_BLOCK_SIZE):((blocknum + 1)* IO_BLOCK_SIZE)-227]
-                    if not check_filled(block, lat_int, lon_int, 100):
-                        print("Bad data in block {0} of {1}".format(blocknum, total_blocks))
+                if total_blocks != 0:
+                    lat_min = 90 * 1.0e7
+                    lat_max = -90 * 1.0e7
+                    lon_min = 180 * 1.0e7
+                    lon_max = -180 * 1.0e7
+                    for blocknum in range(total_blocks):
+                        block = tile[(blocknum * IO_BLOCK_SIZE):((blocknum + 1)* IO_BLOCK_SIZE)-227]
+                        ret = check_filled(block, lat_int, lon_int, 100)
+                        if not ret:
+                            print("Bad data in block {0} of {1}".format(blocknum, total_blocks))
+                        else:
+                            (lat, lon) = ret
+                            lat_min = min(lat_min, lat)
+                            lat_max = max(lat_max, lat)
+                            lon_min = min(lon_min, lon)
+                            lon_max = max(lon_max, lon)
+                    lat_min *= 1.0e-7
+                    lat_max *= 1.0e-7
+                    lon_min *= 1.0e-7
+                    lon_max *= 1.0e-7
+                    print("Tile covers ({0},{1}) to ({2},{3})".format(lat_min, lon_min, lat_max, lon_max))
+                    print("Tile size is ({0:.4f}, {1:.4f}) degrees".format(lat_max-lat_min, lon_max-lon_min))
             else:
                 print("Bad tile: " + file)
     print("Done!")

+ 10 - 39
terrain_gen.py

@@ -30,6 +30,8 @@ TERRAIN_GRID_BLOCK_SIZE_Y = (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_Y)
 TERRAIN_GRID_FORMAT_VERSION = 1
 
 IO_BLOCK_SIZE = 2048
+IO_BLOCK_DATA_SIZE = 1821
+IO_BLOCK_TRAILER_SIZE = IO_BLOCK_SIZE - IO_BLOCK_DATA_SIZE
 
 #GRID_SPACING = 100
 
@@ -91,7 +93,7 @@ def pos_from_file_offset(lat_degrees, lon_degrees, file_offset, 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):
         '''
@@ -203,6 +205,7 @@ class DataFile(object):
         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)
+        buf += struct.pack("%uB" % IO_BLOCK_TRAILER_SIZE, *[0]*IO_BLOCK_TRAILER_SIZE)
         return buf
 
     def write(self, block):
@@ -210,7 +213,7 @@ class DataFile(object):
         self.seek_offset(block)
         block.crc = 0
         buf = self.pack(block)
-        block.crc = crc16.crc16xmodem(buf)
+        block.crc = crc16.crc16xmodem(buf[:IO_BLOCK_DATA_SIZE])
         buf = self.pack(block)
         self.fh.write(buf)
 
@@ -244,10 +247,13 @@ def create_degree(downloader, lat, lon, folder, grid_spacing):
 
     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
+    blocknum = -1
 
-    for blocknum in range(total_blocks):
+    while True:
+        blocknum += 1
         (lat_e7, lon_e7) = pos_from_file_offset(lat_int, lon_int, blocknum * IO_BLOCK_SIZE, grid_spacing)
+        if lat_e7*1.0e-7 - lat_int >= 1.0:
+            break
         lat = lat_e7 * 1.0e-7
         lon = lon_e7 * 1.0e-7
         grid = GridBlock(lat_int, lon_int, lat, lon, grid_spacing)
@@ -282,38 +288,3 @@ def create_degree(downloader, lat, lon, folder, grid_spacing):
 
     dfile.finalise()
 
-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)
-
-    print("Doing " + folderthis)
-
-    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)
-            create_degree(downloader, lat_int, lon_int, folderthis, spacing)
-
-    create_degree(downloader, lat, lon, folderthis, spacing)
-    #numpercent += 1