terrain_gen.py 11 KB

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