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