APM:Libraries
AP_Terrain.cpp
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 
16 #include <AP_HAL/AP_HAL.h>
17 #include <AP_Common/AP_Common.h>
18 #include <AP_Math/AP_Math.h>
20 #include <GCS_MAVLink/GCS.h>
21 #include <DataFlash/DataFlash.h>
22 #include "AP_Terrain.h"
23 
24 #if AP_TERRAIN_AVAILABLE
25 
26 #include <assert.h>
27 #include <stdio.h>
28 #if HAL_OS_POSIX_IO
29 #include <unistd.h>
30 #include <sys/stat.h>
31 #include <fcntl.h>
32 #endif
33 #include <sys/types.h>
34 #include <errno.h>
35 
36 extern const AP_HAL::HAL& hal;
37 
38 // table of user settable parameters
39 const AP_Param::GroupInfo AP_Terrain::var_info[] = {
40  // @Param: ENABLE
41  // @DisplayName: Terrain data enable
42  // @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.
43  // @Values: 0:Disable,1:Enable
44  // @User: Advanced
45  AP_GROUPINFO_FLAGS("ENABLE", 0, AP_Terrain, enable, 1, AP_PARAM_FLAG_ENABLE),
46 
47  // @Param: SPACING
48  // @DisplayName: Terrain grid spacing
49  // @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.
50  // @Units: m
51  // @Increment: 1
52  // @User: Advanced
53  AP_GROUPINFO("SPACING", 1, AP_Terrain, grid_spacing, 100),
54 
56 };
57 
58 // constructor
59 AP_Terrain::AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rally &_rally) :
60  ahrs(_ahrs),
61  mission(_mission),
62  rally(_rally),
63  disk_io_state(DiskIoIdle),
64  fd(-1),
65  timer_setup(false),
66  file_lat_degrees(0),
67  file_lon_degrees(0),
68  io_failure(false),
69  directory_created(false),
70  home_height(0),
71  have_current_loc_height(false),
72  last_current_loc_height(0)
73 {
74  AP_Param::setup_object_defaults(this, var_info);
75  memset(&home_loc, 0, sizeof(home_loc));
76  memset(&disk_block, 0, sizeof(disk_block));
77  memset(last_request_time_ms, 0, sizeof(last_request_time_ms));
78 }
79 
80 /*
81  return terrain height in meters above average sea level (WGS84) for
82  a given position
83 
84  This is the base function that other height calculations are derived
85  from. The functions below are more convenient for most uses
86 
87  This function costs about 20 microseconds on Pixhawk
88  */
89 bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected)
90 {
91  if (!enable || !allocate()) {
92  return false;
93  }
94 
95  // quick access for home altitude
96  if (loc.lat == home_loc.lat &&
97  loc.lng == home_loc.lng) {
98  height = home_height;
99  // apply correction which assumes home altitude is at terrain altitude
100  if (corrected) {
101  height += (ahrs.get_home().alt * 0.01f) - home_height;
102  }
103  return true;
104  }
105 
106  struct grid_info info;
107 
108  calculate_grid_info(loc, info);
109 
110  // find the grid
111  const struct grid_block &grid = find_grid_cache(info).grid;
112 
113  /*
114  note that we rely on the one square overlap to ensure these
115  calculations don't go past the end of the arrays
116  */
117  ASSERT_RANGE(info.idx_x, 0, TERRAIN_GRID_BLOCK_SIZE_X-2);
118  ASSERT_RANGE(info.idx_y, 0, TERRAIN_GRID_BLOCK_SIZE_Y-2);
119 
120 
121  // check we have all 4 required heights
122  if (!check_bitmap(grid, info.idx_x, info.idx_y) ||
123  !check_bitmap(grid, info.idx_x, info.idx_y+1) ||
124  !check_bitmap(grid, info.idx_x+1, info.idx_y) ||
125  !check_bitmap(grid, info.idx_x+1, info.idx_y+1)) {
126  return false;
127  }
128 
129  // hXY are the heights of the 4 surrounding grid points
130  int16_t h00, h01, h10, h11;
131 
132  h00 = grid.height[info.idx_x+0][info.idx_y+0];
133  h01 = grid.height[info.idx_x+0][info.idx_y+1];
134  h10 = grid.height[info.idx_x+1][info.idx_y+0];
135  h11 = grid.height[info.idx_x+1][info.idx_y+1];
136 
137  // do a simple dual linear interpolation. We could do something
138  // fancier, but it probably isn't worth it as long as the
139  // grid_spacing is kept small enough
140  float avg1 = (1.0f-info.frac_x) * h00 + info.frac_x * h10;
141  float avg2 = (1.0f-info.frac_x) * h01 + info.frac_x * h11;
142  float avg = (1.0f-info.frac_y) * avg1 + info.frac_y * avg2;
143 
144  height = avg;
145 
146  if (loc.lat == ahrs.get_home().lat &&
147  loc.lng == ahrs.get_home().lng) {
148  // remember home altitude as a special case
149  home_height = height;
150  home_loc = loc;
151  }
152 
153  // apply correction which assumes home altitude is at terrain altitude
154  if (corrected) {
155  height += (ahrs.get_home().alt * 0.01f) - home_height;
156  }
157 
158  return true;
159 }
160 
161 
162 /*
163  find difference between home terrain height and the terrain
164  height at the current location in meters. A positive result
165  means the terrain is higher than home.
166 
167  return false is terrain at the current location or at home
168  location is not available
169 
170  If extrapolate is true then allow return of an extrapolated
171  terrain altitude based on the last available data
172 */
173 bool AP_Terrain::height_terrain_difference_home(float &terrain_difference, bool extrapolate)
174 {
175  float height_home, height_loc;
176  if (!height_amsl(ahrs.get_home(), height_home, false)) {
177  // we don't know the height of home
178  return false;
179  }
180 
181  Location loc;
182  if (!ahrs.get_position(loc)) {
183  // we don't know where we are
184  return false;
185  }
186 
187  if (!height_amsl(loc, height_loc, false)) {
188  if (!extrapolate || !have_current_loc_height) {
189  // we don't know the height of the given location
190  return false;
191  }
192  // we don't have data at the current location, but the caller
193  // has asked for extrapolation, so use the last available
194  // terrain height. This can be used to fill in while new data
195  // is fetched. It should be very rarely used
196  height_loc = last_current_loc_height;
197  }
198 
199  terrain_difference = height_loc - height_home;
200 
201  return true;
202 }
203 
204 /*
205  return current height above terrain at current AHRS
206  position.
207 
208  If extrapolate is true then extrapolate from most recently
209  available terrain data is terrain data is not available for the
210  current location.
211 
212  Return true if height is available, otherwise false.
213 */
214 bool AP_Terrain::height_above_terrain(float &terrain_altitude, bool extrapolate)
215 {
216  float terrain_difference;
217  if (!height_terrain_difference_home(terrain_difference, extrapolate)) {
218  return false;
219  }
220 
221  float relative_home_altitude;
222  ahrs.get_relative_position_D_home(relative_home_altitude);
223  relative_home_altitude = -relative_home_altitude;
224 
225  terrain_altitude = relative_home_altitude - terrain_difference;
226  return true;
227 }
228 
229 /*
230  return estimated equivalent relative-to-home altitude in meters
231  of a given height above the terrain at the current location
232 
233  This function allows existing height controllers which work on
234  barometric altitude (relative to home) to be used with terrain
235  based target altitude, by translating the "above terrain" altitude
236  into an equivalent barometric relative height.
237 
238  return false if terrain data is not available either at the given
239  location or at the home location.
240 
241  If extrapolate is true then allow return of an extrapolated
242  terrain altitude based on the last available data
243 */
244 bool AP_Terrain::height_relative_home_equivalent(float terrain_altitude,
245  float &relative_home_altitude,
246  bool extrapolate)
247 {
248  float terrain_difference;
249  if (!height_terrain_difference_home(terrain_difference, extrapolate)) {
250  return false;
251  }
252  relative_home_altitude = terrain_altitude + terrain_difference;
253  return true;
254 }
255 
256 
257 /*
258  calculate lookahead rise in terrain. This returns extra altitude
259  needed to clear upcoming terrain in meters
260 */
261 float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio)
262 {
263  if (!enable || !allocate() || grid_spacing <= 0) {
264  return 0;
265  }
266 
267  Location loc;
268  if (!ahrs.get_position(loc)) {
269  // we don't know where we are
270  return 0;
271  }
272  float base_height;
273  if (!height_amsl(loc, base_height, false)) {
274  // we don't know our current terrain height
275  return 0;
276  }
277 
278  float climb = 0;
279  float lookahead_estimate = 0;
280 
281  // check for terrain at grid spacing intervals
282  while (distance > 0) {
283  location_update(loc, bearing, grid_spacing);
284  climb += climb_ratio * grid_spacing;
285  distance -= grid_spacing;
286  float height;
287  if (height_amsl(loc, height, false)) {
288  float rise = (height - base_height) - climb;
289  if (rise > lookahead_estimate) {
290  lookahead_estimate = rise;
291  }
292  }
293  }
294 
295  return lookahead_estimate;
296 }
297 
298 
299 /*
300  1hz update function. This is here to ensure progress is made on disk
301  IO even if no MAVLink send_request() operations are called for a
302  while.
303  */
304 void AP_Terrain::update(void)
305 {
306  // just schedule any needed disk IO
307  schedule_disk_io();
308 
309  // try to ensure the home location is populated
310  float height;
311  height_amsl(ahrs.get_home(), height, false);
312 
313  // update the cached current location height
314  Location loc;
315  bool pos_valid = ahrs.get_position(loc);
316  bool terrain_valid = pos_valid && height_amsl(loc, height, false);
317  if (pos_valid && terrain_valid) {
318  last_current_loc_height = height;
319  have_current_loc_height = true;
320  }
321 
322  // check for pending mission data
323  update_mission_data();
324 
325  // check for pending rally data
326  update_rally_data();
327 
328  // update capabilities and status
329  if (enable) {
330  hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_TERRAIN);
331  if (!pos_valid) {
332  // we don't know where we are
333  system_status = TerrainStatusUnhealthy;
334  } else if (!terrain_valid) {
335  // we don't have terrain data at current location
336  system_status = TerrainStatusUnhealthy;
337  } else {
338  system_status = TerrainStatusOK;
339  }
340  } else {
341  hal.util->clear_capabilities(MAV_PROTOCOL_CAPABILITY_TERRAIN);
342  system_status = TerrainStatusDisabled;
343  }
344 
345 }
346 
347 /*
348  log terrain data to dataflash log
349  */
350 void AP_Terrain::log_terrain_data(DataFlash_Class &dataflash)
351 {
352  if (!enable) {
353  return;
354  }
355  Location loc;
356  if (!ahrs.get_position(loc)) {
357  // we don't know where we are
358  return;
359  }
360  float terrain_height = 0;
361  float current_height = 0;
362  uint16_t pending, loaded;
363 
364  height_amsl(loc, terrain_height, false);
365  height_above_terrain(current_height, true);
366  get_statistics(pending, loaded);
367 
368  struct log_TERRAIN pkt = {
371  status : (uint8_t)status(),
372  lat : loc.lat,
373  lng : loc.lng,
374  spacing : (uint16_t)grid_spacing,
375  terrain_height : terrain_height,
376  current_height : current_height,
377  pending : pending,
378  loaded : loaded
379  };
380  dataflash.WriteBlock(&pkt, sizeof(pkt));
381 }
382 
383 /*
384  allocate terrain cache. Making this dynamically allocated allows
385  memory to be saved when terrain functionality is disabled
386  */
387 bool AP_Terrain::allocate(void)
388 {
389  if (enable == 0) {
390  return false;
391  }
392  if (cache != nullptr) {
393  return true;
394  }
395  cache = (struct grid_cache *)calloc(TERRAIN_GRID_BLOCK_CACHE_SIZE, sizeof(cache[0]));
396  if (cache == nullptr) {
397  enable.set(0);
398  gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed");
399  return false;
400  }
401  cache_size = TERRAIN_GRID_BLOCK_CACHE_SIZE;
402  return true;
403 }
404 
405 #endif // AP_TERRAIN_AVAILABLE
void get_relative_position_D_home(float &posD) const override
void location_update(struct Location &loc, float bearing, float distance)
Definition: location.cpp:115
int32_t lat
Definition: LogStructure.h:737
Object managing Rally Points.
Definition: AP_Rally.h:37
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
Interface definition for the various Ground Control System.
Object managing Mission.
Definition: AP_Mission.h:45
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
void clear_capabilities(uint64_t cap)
Definition: Util.h:18
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_HAL::Util * util
Definition: HAL.h:115
void set_capabilities(uint64_t cap)
Definition: Util.h:17
void WriteBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:481
uint16_t spacing
Definition: LogStructure.h:739
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
GCS & gcs()
float distance
Definition: location.cpp:94
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
uint64_t time_us
Definition: LogStructure.h:735
int32_t lng
Definition: LogStructure.h:738
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
float bearing
Definition: location.cpp:94
uint8_t status
Definition: LogStructure.h:736
uint64_t micros64()
Definition: system.cpp:162
bool get_position(struct Location &loc) const override
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
Common definitions and utility routines for the ArduPilot libraries.
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214