terrain_gen.py 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290
  1. #!/usr/bin/env python
  2. '''
  3. create ardupilot terrain database files
  4. '''
  5. import math, struct, os
  6. import crc16, time, struct
  7. from MAVProxy.modules.mavproxy_map import srtm
  8. # MAVLink sends 4x4 grids
  9. TERRAIN_GRID_MAVLINK_SIZE = 4
  10. # a 2k grid_block on disk contains 8x7 of the mavlink grids. Each
  11. # grid block overlaps by one with its neighbour. This ensures that
  12. # the altitude at any point can be calculated from a single grid
  13. # block
  14. TERRAIN_GRID_BLOCK_MUL_X = 7
  15. TERRAIN_GRID_BLOCK_MUL_Y = 8
  16. # this is the spacing between 32x28 grid blocks, in grid_spacing units
  17. TERRAIN_GRID_BLOCK_SPACING_X = ((TERRAIN_GRID_BLOCK_MUL_X-1)*TERRAIN_GRID_MAVLINK_SIZE)
  18. TERRAIN_GRID_BLOCK_SPACING_Y = ((TERRAIN_GRID_BLOCK_MUL_Y-1)*TERRAIN_GRID_MAVLINK_SIZE)
  19. # giving a total grid size of a disk grid_block of 32x28
  20. TERRAIN_GRID_BLOCK_SIZE_X = (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_X)
  21. TERRAIN_GRID_BLOCK_SIZE_Y = (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_Y)
  22. # format of grid on disk
  23. TERRAIN_GRID_FORMAT_VERSION = 1
  24. IO_BLOCK_SIZE = 2048
  25. IO_BLOCK_DATA_SIZE = 1821
  26. IO_BLOCK_TRAILER_SIZE = IO_BLOCK_SIZE - IO_BLOCK_DATA_SIZE
  27. #GRID_SPACING = 100
  28. def to_float32(f):
  29. '''emulate single precision float'''
  30. return struct.unpack('f', struct.pack('f',f))[0]
  31. LOCATION_SCALING_FACTOR = to_float32(0.011131884502145034)
  32. LOCATION_SCALING_FACTOR_INV = to_float32(89.83204953368922)
  33. def longitude_scale(lat):
  34. '''get longitude scale factor'''
  35. scale = to_float32(math.cos(to_float32(math.radians(lat))))
  36. return max(scale, 0.01)
  37. def get_distance_NE_e7(lat1, lon1, lat2, lon2):
  38. '''get distance tuple between two positions in 1e7 format'''
  39. return ((lat2 - lat1) * LOCATION_SCALING_FACTOR, (lon2 - lon1) * LOCATION_SCALING_FACTOR * longitude_scale(lat1*1.0e-7))
  40. def add_offset(lat_e7, lon_e7, ofs_north, ofs_east):
  41. '''add offset in meters to a position'''
  42. dlat = int(float(ofs_north) * LOCATION_SCALING_FACTOR_INV)
  43. dlng = int((float(ofs_east) * LOCATION_SCALING_FACTOR_INV) / longitude_scale(lat_e7*1.0e-7))
  44. return (int(lat_e7+dlat), int(lon_e7+dlng))
  45. def east_blocks(lat_e7, lon_e7, grid_spacing):
  46. '''work out how many blocks per stride on disk'''
  47. lat2_e7 = lat_e7
  48. lon2_e7 = lon_e7 + 10*1000*1000
  49. # shift another two blocks east to ensure room is available
  50. lat2_e7, lon2_e7 = add_offset(lat2_e7, lon2_e7, 0, 2*grid_spacing*TERRAIN_GRID_BLOCK_SIZE_Y)
  51. offset = get_distance_NE_e7(lat_e7, lon_e7, lat2_e7, lon2_e7)
  52. return int(offset[1] / (grid_spacing*TERRAIN_GRID_BLOCK_SPACING_Y))
  53. def pos_from_file_offset(lat_degrees, lon_degrees, file_offset, grid_spacing):
  54. '''return a lat/lon in 1e7 format given a file offset'''
  55. ref_lat = int(lat_degrees*10*1000*1000)
  56. ref_lon = int(lon_degrees*10*1000*1000)
  57. stride = east_blocks(ref_lat, ref_lon, grid_spacing)
  58. blocks = file_offset // IO_BLOCK_SIZE
  59. grid_idx_x = blocks // stride
  60. grid_idx_y = blocks % stride
  61. idx_x = grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X
  62. idx_y = grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y
  63. offset = (idx_x * grid_spacing, idx_y * grid_spacing)
  64. (lat_e7, lon_e7) = add_offset(ref_lat, ref_lon, offset[0], offset[1])
  65. offset = get_distance_NE_e7(ref_lat, ref_lon, lat_e7, lon_e7)
  66. grid_idx_x = int(idx_x / TERRAIN_GRID_BLOCK_SPACING_X)
  67. grid_idx_y = int(idx_y / TERRAIN_GRID_BLOCK_SPACING_Y)
  68. (lat_e7, lon_e7) = add_offset(ref_lat, ref_lon,
  69. grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X * float(grid_spacing),
  70. grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y * float(grid_spacing))
  71. return (lat_e7, lon_e7)
  72. class GridBlock(object):
  73. def __init__(self, lat_int, lon_int, lat, lon, grid_spacing):
  74. '''
  75. a grid block is a structure in a local file containing height
  76. information. Each grid block is 2048 bytes in size, to keep file IO to
  77. block oriented SD cards efficient
  78. '''
  79. # crc of whole block, taken with crc=0
  80. self.crc = 0
  81. # format version number
  82. self.version = TERRAIN_GRID_FORMAT_VERSION
  83. # grid spacing in meters
  84. self.spacing = grid_spacing
  85. # heights in meters over a 32*28 grid
  86. self.height = []
  87. for x in range(TERRAIN_GRID_BLOCK_SIZE_X):
  88. self.height.append([0]*TERRAIN_GRID_BLOCK_SIZE_Y)
  89. # bitmap of 4x4 grids filled in from GCS (56 bits are used)
  90. self.bitmap = (1<<56)-1
  91. lat_e7 = int(lat * 1.0e7)
  92. lon_e7 = int(lon * 1.0e7)
  93. # grids start on integer degrees. This makes storing terrain data on
  94. # the SD card a bit easier. Note that this relies on the python floor
  95. # behaviour with integer division
  96. self.lat_degrees = lat_int
  97. self.lon_degrees = lon_int
  98. # create reference position for this rounded degree position
  99. ref_lat = self.lat_degrees*10*1000*1000
  100. ref_lon = self.lon_degrees*10*1000*1000
  101. # find offset from reference
  102. offset = get_distance_NE_e7(ref_lat, ref_lon, lat_e7, lon_e7)
  103. offset = (round(offset[0]), round(offset[1]))
  104. # get indices in terms of grid_spacing elements
  105. idx_x = int(offset[0] / self.spacing)
  106. idx_y = int(offset[1] / self.spacing)
  107. # find indexes into 32*28 grids for this degree reference. Note
  108. # the use of TERRAIN_GRID_BLOCK_SPACING_{X,Y} which gives a one square
  109. # overlap between grids
  110. self.grid_idx_x = idx_x // TERRAIN_GRID_BLOCK_SPACING_X
  111. self.grid_idx_y = idx_y // TERRAIN_GRID_BLOCK_SPACING_Y
  112. # calculate lat/lon of SW corner of 32*28 grid_block
  113. (ref_lat, ref_lon) = add_offset(ref_lat, ref_lon,
  114. self.grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X * float(self.spacing),
  115. self.grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y * float(self.spacing))
  116. self.lat = ref_lat
  117. self.lon = ref_lon
  118. def fill(self, gx, gy, altitude):
  119. '''fill a square'''
  120. self.height[gx][gy] = int(altitude)
  121. def blocknum(self):
  122. '''find IO block number'''
  123. stride = east_blocks(self.lat_degrees*1e7, self.lon_degrees*1e7, self.spacing)
  124. return stride * self.grid_idx_x + self.grid_idx_y
  125. class DataFile(object):
  126. def __init__(self, lat, lon, folder):
  127. if lat < 0:
  128. NS = 'S'
  129. else:
  130. NS = 'N'
  131. if lon < 0:
  132. EW = 'W'
  133. else:
  134. EW = 'E'
  135. self.name = folder + "/%c%02u%c%03u.DAT" % (NS, min(abs(int(lat)), 99),
  136. EW, min(abs(int(lon)), 999))
  137. self.tmpname = folder + "/%c%02u%c%03u.DAT.tmp" % (NS, min(abs(int(lat)), 99),
  138. EW, min(abs(int(lon)), 999))
  139. try:
  140. os.mkdir(folder)
  141. except Exception:
  142. pass
  143. if not os.path.exists(self.name):
  144. self.fh = open(self.tmpname, 'w+b')
  145. else:
  146. self.fh = open(self.name, 'r+b')
  147. def finalise(self):
  148. '''finalise file after writing'''
  149. self.fh.close()
  150. #and rename
  151. os.rename(self.tmpname, self.name)
  152. def seek_offset(self, block):
  153. '''seek to right offset'''
  154. # work out how many longitude blocks there are at this latitude
  155. file_offset = block.blocknum() * IO_BLOCK_SIZE
  156. self.fh.seek(file_offset)
  157. def pack(self, block):
  158. '''pack into a block'''
  159. buf = bytes()
  160. buf += struct.pack("<QiiHHH", block.bitmap, block.lat, block.lon, block.crc, block.version, block.spacing)
  161. for gx in range(TERRAIN_GRID_BLOCK_SIZE_X):
  162. buf += struct.pack("<%uh" % TERRAIN_GRID_BLOCK_SIZE_Y, *block.height[gx])
  163. buf += struct.pack("<HHhb", block.grid_idx_x, block.grid_idx_y, block.lon_degrees, block.lat_degrees)
  164. buf += struct.pack("%uB" % IO_BLOCK_TRAILER_SIZE, *[0]*IO_BLOCK_TRAILER_SIZE)
  165. return buf
  166. def write(self, block):
  167. '''write a grid block'''
  168. self.seek_offset(block)
  169. block.crc = 0
  170. buf = self.pack(block)
  171. block.crc = crc16.crc16xmodem(buf[:IO_BLOCK_DATA_SIZE])
  172. buf = self.pack(block)
  173. self.fh.write(buf)
  174. def check_filled(self, block, grid_spacing):
  175. '''read a grid block and check if already filled'''
  176. self.seek_offset(block)
  177. buf = self.fh.read(IO_BLOCK_SIZE)
  178. if len(buf) != IO_BLOCK_SIZE:
  179. return False
  180. (bitmap, lat, lon, crc, version, spacing) = struct.unpack("<QiiHHH", buf[:22])
  181. if (version != TERRAIN_GRID_FORMAT_VERSION or
  182. abs(lat - block.lat)>2 or
  183. abs(lon - block.lon)>2 or
  184. spacing != grid_spacing or
  185. bitmap != (1<<56)-1):
  186. return False
  187. buf = buf[:16] + struct.pack("<H", 0) + buf[18:]
  188. crc2 = crc16.crc16xmodem(buf[:1821])
  189. if crc2 != crc:
  190. return False
  191. return True
  192. def create_degree(downloader, lat, lon, folder, grid_spacing):
  193. '''create data file for one degree lat/lon'''
  194. lat_int = int(math.floor(lat))
  195. lon_int = int(math.floor((lon)))
  196. tiles = {}
  197. dfile = DataFile(lat_int, lon_int, folder)
  198. print("Creating for %d %d" % (lat_int, lon_int))
  199. blocknum = -1
  200. while True:
  201. blocknum += 1
  202. (lat_e7, lon_e7) = pos_from_file_offset(lat_int, lon_int, blocknum * IO_BLOCK_SIZE, grid_spacing)
  203. if lat_e7*1.0e-7 - lat_int >= 1.0:
  204. break
  205. lat = lat_e7 * 1.0e-7
  206. lon = lon_e7 * 1.0e-7
  207. grid = GridBlock(lat_int, lon_int, lat, lon, grid_spacing)
  208. if grid.blocknum() != blocknum:
  209. continue
  210. if dfile.check_filled(grid, grid_spacing):
  211. continue
  212. for gx in range(TERRAIN_GRID_BLOCK_SIZE_X):
  213. for gy in range(TERRAIN_GRID_BLOCK_SIZE_Y):
  214. lat_e7, lon_e7 = add_offset(lat*1.0e7, lon*1.0e7, gx*grid_spacing, gy*grid_spacing)
  215. lat2_int = int(math.floor(lat_e7*1.0e-7))
  216. lon2_int = int(math.floor(lon_e7*1.0e-7))
  217. tile_idx = (lat2_int, lon2_int)
  218. while not tile_idx in tiles:
  219. tile = downloader.getTile(lat2_int, lon2_int)
  220. waited = False
  221. if tile == 0:
  222. print("waiting on download of %d,%d" % (lat2_int, lon2_int))
  223. time.sleep(0.3)
  224. waited = True
  225. continue
  226. if waited:
  227. print("downloaded %d,%d" % (lat2_int, lon2_int))
  228. tiles[tile_idx] = tile
  229. if isinstance(tile, srtm.SRTMOceanTile):
  230. # if it's a blank ocean tile, there's a quicker way to generate the tile
  231. grid.fill(gx, gy, 0)
  232. else:
  233. altitude = tiles[tile_idx].getAltitudeFromLatLon(lat_e7*1.0e-7, lon_e7*1.0e-7)
  234. grid.fill(gx, gy, altitude)
  235. dfile.write(grid)
  236. dfile.finalise()