AP_Terrain.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395
  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. #include <AP_HAL/AP_HAL.h>
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_Math/AP_Math.h>
  16. #include <GCS_MAVLink/GCS_MAVLink.h>
  17. #include <GCS_MAVLink/GCS.h>
  18. #include <AP_Logger/AP_Logger.h>
  19. #include "AP_Terrain.h"
  20. #include <AP_AHRS/AP_AHRS.h>
  21. #if AP_TERRAIN_AVAILABLE
  22. #include <AP_Filesystem/AP_Filesystem.h>
  23. extern const AP_HAL::HAL& hal;
  24. AP_Terrain *AP_Terrain::singleton;
  25. // table of user settable parameters
  26. const AP_Param::GroupInfo AP_Terrain::var_info[] = {
  27. // @Param: ENABLE
  28. // @DisplayName: Terrain data enable
  29. // @Description: enable terrain data. This enables the vehicle storing a database of terrain data on the SD card. The terrain data is requested from the ground station as needed, and stored for later use on the SD card. To be useful the ground station must support TERRAIN_REQUEST messages and have access to a terrain database, such as the SRTM database.
  30. // @Values: 0:Disable,1:Enable
  31. // @User: Advanced
  32. AP_GROUPINFO_FLAGS("ENABLE", 0, AP_Terrain, enable, 1, AP_PARAM_FLAG_ENABLE),
  33. // @Param: SPACING
  34. // @DisplayName: Terrain grid spacing
  35. // @Description: Distance between terrain grid points in meters. This controls the horizontal resolution of the terrain data that is stored on te SD card and requested from the ground station. If your GCS is using the worldwide SRTM database then a resolution of 100 meters is appropriate. Some parts of the world may have higher resolution data available, such as 30 meter data available in the SRTM database in the USA. The grid spacing also controls how much data is kept in memory during flight. A larger grid spacing will allow for a larger amount of data in memory. A grid spacing of 100 meters results in the vehicle keeping 12 grid squares in memory with each grid square having a size of 2.7 kilometers by 3.2 kilometers. Any additional grid squares are stored on the SD once they are fetched from the GCS and will be demand loaded as needed.
  36. // @Units: m
  37. // @Increment: 1
  38. // @User: Advanced
  39. AP_GROUPINFO("SPACING", 1, AP_Terrain, grid_spacing, 100),
  40. AP_GROUPEND
  41. };
  42. // constructor
  43. AP_Terrain::AP_Terrain(const AP_Mission &_mission) :
  44. mission(_mission),
  45. disk_io_state(DiskIoIdle),
  46. fd(-1)
  47. {
  48. AP_Param::setup_object_defaults(this, var_info);
  49. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  50. if (singleton != nullptr) {
  51. AP_HAL::panic("Terrain must be singleton");
  52. }
  53. #endif
  54. singleton = this;
  55. }
  56. /*
  57. return terrain height in meters above average sea level (WGS84) for
  58. a given position
  59. This is the base function that other height calculations are derived
  60. from. The functions below are more convenient for most uses
  61. This function costs about 20 microseconds on Pixhawk
  62. */
  63. bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected)
  64. {
  65. if (!allocate()) {
  66. return false;
  67. }
  68. const AP_AHRS &ahrs = AP::ahrs();
  69. // quick access for home altitude
  70. if (loc.lat == home_loc.lat &&
  71. loc.lng == home_loc.lng) {
  72. height = home_height;
  73. // apply correction which assumes home altitude is at terrain altitude
  74. if (corrected) {
  75. height += (ahrs.get_home().alt * 0.01f) - home_height;
  76. }
  77. return true;
  78. }
  79. struct grid_info info;
  80. calculate_grid_info(loc, info);
  81. // find the grid
  82. const struct grid_block &grid = find_grid_cache(info).grid;
  83. /*
  84. note that we rely on the one square overlap to ensure these
  85. calculations don't go past the end of the arrays
  86. */
  87. ASSERT_RANGE(info.idx_x, 0, TERRAIN_GRID_BLOCK_SIZE_X-2);
  88. ASSERT_RANGE(info.idx_y, 0, TERRAIN_GRID_BLOCK_SIZE_Y-2);
  89. // check we have all 4 required heights
  90. if (!check_bitmap(grid, info.idx_x, info.idx_y) ||
  91. !check_bitmap(grid, info.idx_x, info.idx_y+1) ||
  92. !check_bitmap(grid, info.idx_x+1, info.idx_y) ||
  93. !check_bitmap(grid, info.idx_x+1, info.idx_y+1)) {
  94. return false;
  95. }
  96. // hXY are the heights of the 4 surrounding grid points
  97. int16_t h00, h01, h10, h11;
  98. h00 = grid.height[info.idx_x+0][info.idx_y+0];
  99. h01 = grid.height[info.idx_x+0][info.idx_y+1];
  100. h10 = grid.height[info.idx_x+1][info.idx_y+0];
  101. h11 = grid.height[info.idx_x+1][info.idx_y+1];
  102. // do a simple dual linear interpolation. We could do something
  103. // fancier, but it probably isn't worth it as long as the
  104. // grid_spacing is kept small enough
  105. float avg1 = (1.0f-info.frac_x) * h00 + info.frac_x * h10;
  106. float avg2 = (1.0f-info.frac_x) * h01 + info.frac_x * h11;
  107. float avg = (1.0f-info.frac_y) * avg1 + info.frac_y * avg2;
  108. height = avg;
  109. if (loc.lat == ahrs.get_home().lat &&
  110. loc.lng == ahrs.get_home().lng) {
  111. // remember home altitude as a special case
  112. home_height = height;
  113. home_loc = loc;
  114. }
  115. // apply correction which assumes home altitude is at terrain altitude
  116. if (corrected) {
  117. height += (ahrs.get_home().alt * 0.01f) - home_height;
  118. }
  119. return true;
  120. }
  121. /*
  122. find difference between home terrain height and the terrain
  123. height at the current location in meters. A positive result
  124. means the terrain is higher than home.
  125. return false is terrain at the current location or at home
  126. location is not available
  127. If extrapolate is true then allow return of an extrapolated
  128. terrain altitude based on the last available data
  129. */
  130. bool AP_Terrain::height_terrain_difference_home(float &terrain_difference, bool extrapolate)
  131. {
  132. const AP_AHRS &ahrs = AP::ahrs();
  133. float height_home, height_loc;
  134. if (!height_amsl(ahrs.get_home(), height_home, false)) {
  135. // we don't know the height of home
  136. return false;
  137. }
  138. Location loc;
  139. if (!ahrs.get_position(loc)) {
  140. // we don't know where we are
  141. return false;
  142. }
  143. if (!height_amsl(loc, height_loc, false)) {
  144. if (!extrapolate || !have_current_loc_height) {
  145. // we don't know the height of the given location
  146. return false;
  147. }
  148. // we don't have data at the current location, but the caller
  149. // has asked for extrapolation, so use the last available
  150. // terrain height. This can be used to fill in while new data
  151. // is fetched. It should be very rarely used
  152. height_loc = last_current_loc_height;
  153. }
  154. terrain_difference = height_loc - height_home;
  155. return true;
  156. }
  157. /*
  158. return current height above terrain at current AHRS
  159. position.
  160. If extrapolate is true then extrapolate from most recently
  161. available terrain data is terrain data is not available for the
  162. current location.
  163. Return true if height is available, otherwise false.
  164. */
  165. bool AP_Terrain::height_above_terrain(float &terrain_altitude, bool extrapolate)
  166. {
  167. float terrain_difference;
  168. if (!height_terrain_difference_home(terrain_difference, extrapolate)) {
  169. return false;
  170. }
  171. float relative_home_altitude;
  172. AP::ahrs().get_relative_position_D_home(relative_home_altitude);
  173. relative_home_altitude = -relative_home_altitude;
  174. terrain_altitude = relative_home_altitude - terrain_difference;
  175. return true;
  176. }
  177. /*
  178. return estimated equivalent relative-to-home altitude in meters
  179. of a given height above the terrain at the current location
  180. This function allows existing height controllers which work on
  181. barometric altitude (relative to home) to be used with terrain
  182. based target altitude, by translating the "above terrain" altitude
  183. into an equivalent barometric relative height.
  184. return false if terrain data is not available either at the given
  185. location or at the home location.
  186. If extrapolate is true then allow return of an extrapolated
  187. terrain altitude based on the last available data
  188. */
  189. bool AP_Terrain::height_relative_home_equivalent(float terrain_altitude,
  190. float &relative_home_altitude,
  191. bool extrapolate)
  192. {
  193. float terrain_difference;
  194. if (!height_terrain_difference_home(terrain_difference, extrapolate)) {
  195. return false;
  196. }
  197. relative_home_altitude = terrain_altitude + terrain_difference;
  198. return true;
  199. }
  200. /*
  201. calculate lookahead rise in terrain. This returns extra altitude
  202. needed to clear upcoming terrain in meters
  203. */
  204. float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio)
  205. {
  206. if (!allocate() || grid_spacing <= 0) {
  207. return 0;
  208. }
  209. Location loc;
  210. if (!AP::ahrs().get_position(loc)) {
  211. // we don't know where we are
  212. return 0;
  213. }
  214. float base_height;
  215. if (!height_amsl(loc, base_height, false)) {
  216. // we don't know our current terrain height
  217. return 0;
  218. }
  219. float climb = 0;
  220. float lookahead_estimate = 0;
  221. // check for terrain at grid spacing intervals
  222. while (distance > 0) {
  223. loc.offset_bearing(bearing, grid_spacing);
  224. climb += climb_ratio * grid_spacing;
  225. distance -= grid_spacing;
  226. float height;
  227. if (height_amsl(loc, height, false)) {
  228. float rise = (height - base_height) - climb;
  229. if (rise > lookahead_estimate) {
  230. lookahead_estimate = rise;
  231. }
  232. }
  233. }
  234. return lookahead_estimate;
  235. }
  236. /*
  237. 1hz update function. This is here to ensure progress is made on disk
  238. IO even if no MAVLink send_request() operations are called for a
  239. while.
  240. */
  241. void AP_Terrain::update(void)
  242. {
  243. // just schedule any needed disk IO
  244. schedule_disk_io();
  245. const AP_AHRS &ahrs = AP::ahrs();
  246. // try to ensure the home location is populated
  247. float height;
  248. height_amsl(ahrs.get_home(), height, false);
  249. // update the cached current location height
  250. Location loc;
  251. bool pos_valid = ahrs.get_position(loc);
  252. bool terrain_valid = pos_valid && height_amsl(loc, height, false);
  253. if (pos_valid && terrain_valid) {
  254. last_current_loc_height = height;
  255. have_current_loc_height = true;
  256. }
  257. // check for pending mission data
  258. update_mission_data();
  259. // check for pending rally data
  260. update_rally_data();
  261. // update capabilities and status
  262. if (allocate()) {
  263. if (!pos_valid) {
  264. // we don't know where we are
  265. system_status = TerrainStatusUnhealthy;
  266. } else if (!terrain_valid) {
  267. // we don't have terrain data at current location
  268. system_status = TerrainStatusUnhealthy;
  269. } else {
  270. system_status = TerrainStatusOK;
  271. }
  272. } else {
  273. system_status = TerrainStatusDisabled;
  274. }
  275. }
  276. void AP_Terrain::log_terrain_data()
  277. {
  278. if (!allocate()) {
  279. return;
  280. }
  281. Location loc;
  282. if (!AP::ahrs().get_position(loc)) {
  283. // we don't know where we are
  284. return;
  285. }
  286. float terrain_height = 0;
  287. float current_height = 0;
  288. uint16_t pending, loaded;
  289. height_amsl(loc, terrain_height, false);
  290. height_above_terrain(current_height, true);
  291. get_statistics(pending, loaded);
  292. struct log_TERRAIN pkt = {
  293. LOG_PACKET_HEADER_INIT(LOG_TERRAIN_MSG),
  294. time_us : AP_HAL::micros64(),
  295. status : (uint8_t)status(),
  296. lat : loc.lat,
  297. lng : loc.lng,
  298. spacing : (uint16_t)grid_spacing,
  299. terrain_height : terrain_height,
  300. current_height : current_height,
  301. pending : pending,
  302. loaded : loaded
  303. };
  304. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  305. }
  306. /*
  307. allocate terrain cache. Making this dynamically allocated allows
  308. memory to be saved when terrain functionality is disabled
  309. */
  310. bool AP_Terrain::allocate(void)
  311. {
  312. if (enable == 0) {
  313. return false;
  314. }
  315. if (cache != nullptr) {
  316. return true;
  317. }
  318. cache = (struct grid_cache *)calloc(TERRAIN_GRID_BLOCK_CACHE_SIZE, sizeof(cache[0]));
  319. if (cache == nullptr) {
  320. enable.set(0);
  321. gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed");
  322. return false;
  323. }
  324. cache_size = TERRAIN_GRID_BLOCK_CACHE_SIZE;
  325. return true;
  326. }
  327. #endif // AP_TERRAIN_AVAILABLE