create_terrain.py 11 KB

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