AP_Terrain.h 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_HAL/AP_HAL.h>
  16. #include <AP_Common/Location.h>
  17. #include <AP_Filesystem/AP_Filesystem.h>
  18. #if HAVE_FILESYSTEM_SUPPORT && defined(HAL_BOARD_TERRAIN_DIRECTORY)
  19. #define AP_TERRAIN_AVAILABLE 1
  20. #else
  21. #define AP_TERRAIN_AVAILABLE 0
  22. #endif
  23. #if AP_TERRAIN_AVAILABLE
  24. #include <AP_Param/AP_Param.h>
  25. #include <AP_Mission/AP_Mission.h>
  26. #define TERRAIN_DEBUG 0
  27. // MAVLink sends 4x4 grids
  28. #define TERRAIN_GRID_MAVLINK_SIZE 4
  29. // a 2k grid_block on disk contains 8x7 of the mavlink grids. Each
  30. // grid block overlaps by one with its neighbour. This ensures that
  31. // the altitude at any point can be calculated from a single grid
  32. // block
  33. #define TERRAIN_GRID_BLOCK_MUL_X 7
  34. #define TERRAIN_GRID_BLOCK_MUL_Y 8
  35. // this is the spacing between 32x28 grid blocks, in grid_spacing units
  36. #define TERRAIN_GRID_BLOCK_SPACING_X ((TERRAIN_GRID_BLOCK_MUL_X-1)*TERRAIN_GRID_MAVLINK_SIZE)
  37. #define TERRAIN_GRID_BLOCK_SPACING_Y ((TERRAIN_GRID_BLOCK_MUL_Y-1)*TERRAIN_GRID_MAVLINK_SIZE)
  38. // giving a total grid size of a disk grid_block of 32x28
  39. #define TERRAIN_GRID_BLOCK_SIZE_X (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_X)
  40. #define TERRAIN_GRID_BLOCK_SIZE_Y (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_Y)
  41. // number of grid_blocks in the LRU memory cache
  42. #define TERRAIN_GRID_BLOCK_CACHE_SIZE 12
  43. // format of grid on disk
  44. #define TERRAIN_GRID_FORMAT_VERSION 1
  45. #if TERRAIN_DEBUG
  46. #define ASSERT_RANGE(v,minv,maxv) assert((v)<=(maxv)&&(v)>=(minv))
  47. #else
  48. #define ASSERT_RANGE(v,minv,maxv)
  49. #endif
  50. /*
  51. Data conventions in this library:
  52. array[x][y]: x is increasing north, y is increasing east
  53. array[x]: low order bits increase east first
  54. bitmap: low order bits increase east first
  55. file: first entries increase east, then north
  56. */
  57. class AP_Terrain {
  58. public:
  59. AP_Terrain(const AP_Mission &_mission);
  60. /* Do not allow copies */
  61. AP_Terrain(const AP_Terrain &other) = delete;
  62. AP_Terrain &operator=(const AP_Terrain&) = delete;
  63. static AP_Terrain *get_singleton(void) { return singleton; }
  64. enum TerrainStatus {
  65. TerrainStatusDisabled = 0, // not enabled
  66. TerrainStatusUnhealthy = 1, // no terrain data for current location
  67. TerrainStatusOK = 2 // terrain data available
  68. };
  69. static const struct AP_Param::GroupInfo var_info[];
  70. // update terrain state. Should be called at 1Hz or more
  71. void update(void);
  72. bool enabled() const { return enable; }
  73. // return status enum for health reporting
  74. enum TerrainStatus status(void) const { return system_status; }
  75. // send any pending terrain request message
  76. void send_request(mavlink_channel_t chan);
  77. // handle terrain data and reports from GCS
  78. void send_terrain_report(mavlink_channel_t chan, const Location &loc, bool extrapolate);
  79. void handle_data(mavlink_channel_t chan, const mavlink_message_t &msg);
  80. void handle_terrain_check(mavlink_channel_t chan, const mavlink_message_t &msg);
  81. void handle_terrain_data(const mavlink_message_t &msg);
  82. /*
  83. find the terrain height in meters above sea level for a location
  84. return false if not available
  85. if corrected is true then terrain alt is adjusted so that
  86. the terrain altitude matches the home altitude at the home location
  87. (i.e. we assume home is at the terrain altitude)
  88. */
  89. bool height_amsl(const Location &loc, float &height, bool corrected);
  90. /*
  91. find difference between home terrain height and the terrain
  92. height at the current location in meters. A positive result
  93. means the terrain is higher than home.
  94. return false is terrain at the current location or at home
  95. location is not available
  96. If extrapolate is true then allow return of an extrapolated
  97. terrain altitude based on the last available data
  98. */
  99. bool height_terrain_difference_home(float &terrain_difference,
  100. bool extrapolate = false);
  101. /*
  102. return estimated equivalent relative-to-home altitude in meters
  103. of a given height above the terrain at the current location
  104. This function allows existing height controllers which work on
  105. barometric altitude (relative to home) to be used with terrain
  106. based target altitude, by translating the "above terrain" altitude
  107. into an equivalent barometric relative height.
  108. return false if terrain data is not available either at the given
  109. location or at the home location.
  110. If extrapolate is true then allow return of an extrapolated
  111. terrain altitude based on the last available data
  112. */
  113. bool height_relative_home_equivalent(float terrain_altitude,
  114. float &relative_altitude,
  115. bool extrapolate = false);
  116. /*
  117. return current height above terrain at current AHRS
  118. position.
  119. If extrapolate is true then extrapolate from most recently
  120. available terrain data is terrain data is not available for the
  121. current location.
  122. Return true if height is available, otherwise false.
  123. */
  124. bool height_above_terrain(float &terrain_altitude, bool extrapolate = false);
  125. /*
  126. calculate lookahead rise in terrain. This returns extra altitude
  127. needed to clear upcoming terrain in meters
  128. */
  129. float lookahead(float bearing, float distance, float climb_ratio);
  130. /*
  131. log terrain status to AP_Logger
  132. */
  133. void log_terrain_data();
  134. /*
  135. get some statistics for TERRAIN_REPORT
  136. */
  137. void get_statistics(uint16_t &pending, uint16_t &loaded);
  138. private:
  139. // allocate the terrain subsystem data
  140. bool allocate(void);
  141. /*
  142. a grid block is a structure in a local file containing height
  143. information. Each grid block is 2048 in size, to keep file IO to
  144. block oriented SD cards efficient
  145. */
  146. struct PACKED grid_block {
  147. // bitmap of 4x4 grids filled in from GCS (56 bits are used)
  148. uint64_t bitmap;
  149. // south west corner of block in degrees*10^7
  150. int32_t lat;
  151. int32_t lon;
  152. // crc of whole block, taken with crc=0
  153. uint16_t crc;
  154. // format version number
  155. uint16_t version;
  156. // grid spacing in meters
  157. uint16_t spacing;
  158. // heights in meters over a 32*28 grid
  159. int16_t height[TERRAIN_GRID_BLOCK_SIZE_X][TERRAIN_GRID_BLOCK_SIZE_Y];
  160. // indices info 32x28 grids for this degree reference
  161. uint16_t grid_idx_x;
  162. uint16_t grid_idx_y;
  163. // rounded latitude/longitude in degrees.
  164. int16_t lon_degrees;
  165. int8_t lat_degrees;
  166. };
  167. /*
  168. grid_block for disk IO, aligned on 2048 byte boundaries
  169. */
  170. union grid_io_block {
  171. struct grid_block block;
  172. uint8_t buffer[2048];
  173. };
  174. enum GridCacheState {
  175. GRID_CACHE_INVALID=0, // when first initialised
  176. GRID_CACHE_DISKWAIT=1, // when waiting for disk read
  177. GRID_CACHE_VALID=2, // when at least partially valid
  178. GRID_CACHE_DIRTY=3 // when updates have been made, and
  179. // disk write needed
  180. };
  181. /*
  182. a grid_block plus some meta data used for requesting new blocks
  183. */
  184. struct grid_cache {
  185. struct grid_block grid;
  186. volatile enum GridCacheState state;
  187. // the last time access was requested to this block, used for LRU
  188. uint32_t last_access_ms;
  189. };
  190. /*
  191. grid_info is a broken down representation of a Location, giving
  192. the index terms for finding the right grid
  193. */
  194. struct grid_info {
  195. // rounded latitude/longitude in degrees.
  196. int8_t lat_degrees;
  197. int16_t lon_degrees;
  198. // lat and lon of SW corner of this 32*28 grid, *10^7 degrees
  199. int32_t grid_lat;
  200. int32_t grid_lon;
  201. // indices info 32x28 grids for this degree reference
  202. uint16_t grid_idx_x;
  203. uint16_t grid_idx_y;
  204. // indexes into 32x28 grid
  205. uint8_t idx_x; // north (0..27)
  206. uint8_t idx_y; // east (0..31)
  207. // fraction within the grid square
  208. float frac_x; // north (0..1)
  209. float frac_y; // east (0..1)
  210. // file offset of this grid
  211. uint32_t file_offset;
  212. };
  213. // given a location, fill a grid_info structure
  214. void calculate_grid_info(const Location &loc, struct grid_info &info) const;
  215. /*
  216. find a grid structure given a grid_info
  217. */
  218. struct grid_cache &find_grid_cache(const struct grid_info &info);
  219. /*
  220. calculate bit number in grid_block bitmap. This corresponds to a
  221. bit representing a 4x4 mavlink transmitted block
  222. */
  223. uint8_t grid_bitnum(uint8_t idx_x, uint8_t idx_y);
  224. /*
  225. given a grid_info check that a given idx_x/idx_y is available (set
  226. in the bitmap)
  227. */
  228. bool check_bitmap(const struct grid_block &grid, uint8_t idx_x, uint8_t idx_y);
  229. /*
  230. request any missing 4x4 grids from a block
  231. */
  232. bool request_missing(mavlink_channel_t chan, struct grid_cache &gcache);
  233. bool request_missing(mavlink_channel_t chan, const struct grid_info &info);
  234. /*
  235. look for blocks that need to be read/written to disk
  236. */
  237. void schedule_disk_io(void);
  238. /*
  239. get some statistics for TERRAIN_REPORT
  240. */
  241. uint8_t bitcount64(uint64_t b);
  242. /*
  243. disk IO functions
  244. */
  245. int16_t find_io_idx(enum GridCacheState state);
  246. uint16_t get_block_crc(struct grid_block &block);
  247. void check_disk_read(void);
  248. void check_disk_write(void);
  249. void io_timer(void);
  250. void open_file(void);
  251. void seek_offset(void);
  252. void write_block(void);
  253. void read_block(void);
  254. /*
  255. check for missing mission terrain data
  256. */
  257. void update_mission_data(void);
  258. /*
  259. check for missing rally data
  260. */
  261. void update_rally_data(void);
  262. // parameters
  263. AP_Int8 enable;
  264. AP_Int16 grid_spacing; // meters between grid points
  265. // reference to AP_Mission, so we can ask preload terrain data for
  266. // all waypoints
  267. const AP_Mission &mission;
  268. // cache of grids in memory, LRU
  269. uint8_t cache_size = 0;
  270. struct grid_cache *cache = nullptr;
  271. // a grid_cache block waiting for disk IO
  272. enum DiskIoState {
  273. DiskIoIdle = 0,
  274. DiskIoWaitWrite = 1,
  275. DiskIoWaitRead = 2,
  276. DiskIoDoneRead = 3,
  277. DiskIoDoneWrite = 4
  278. };
  279. volatile enum DiskIoState disk_io_state;
  280. union grid_io_block disk_block;
  281. // last time we asked for more grids
  282. uint32_t last_request_time_ms[MAVLINK_COMM_NUM_BUFFERS];
  283. static const uint64_t bitmap_mask = (((uint64_t)1U)<<(TERRAIN_GRID_BLOCK_MUL_X*TERRAIN_GRID_BLOCK_MUL_Y)) - 1;
  284. // open file handle on degree file
  285. int fd;
  286. // has the timer been setup?
  287. bool timer_setup;
  288. // degrees lat and lon of file
  289. int8_t file_lat_degrees;
  290. int16_t file_lon_degrees;
  291. // do we have an IO failure
  292. volatile bool io_failure;
  293. // have we created the terrain directory?
  294. bool directory_created;
  295. // cache the home altitude, as it is needed so often
  296. float home_height;
  297. Location home_loc;
  298. // cache the last terrain height (AMSL) of the AHRS current
  299. // location. This is used for extrapolation when terrain data is
  300. // temporarily unavailable
  301. bool have_current_loc_height;
  302. float last_current_loc_height;
  303. // next mission command to check
  304. uint16_t next_mission_index;
  305. // next mission position to check
  306. uint8_t next_mission_pos;
  307. // last time the mission changed
  308. uint32_t last_mission_change_ms;
  309. // grid spacing during mission check
  310. uint16_t last_mission_spacing;
  311. // next rally command to check
  312. uint16_t next_rally_index;
  313. // last time the rally points changed
  314. uint32_t last_rally_change_ms;
  315. // grid spacing during rally check
  316. uint16_t last_rally_spacing;
  317. char *file_path = nullptr;
  318. // status
  319. enum TerrainStatus system_status = TerrainStatusDisabled;
  320. static AP_Terrain *singleton;
  321. };
  322. #endif // AP_TERRAIN_AVAILABLE