Skip to content

Commit 653c484

Browse files
committed
AP_Terrain: check for old DAT files in pre-arm
Add a version_minor to the terrain data structure to allow checking for old DAT files. This pushes users towards downloading new terrain data to avoid issues with old terrain data that have been recently fixed. If the user has not set the TERRAIN_OPTIONS bit to accept old terrain data then they will get a pre-arm error if any old terrain data is found during the normal pre-flight check of terrain data. Note that this doesn't check every block in all DAT files as that will take too long, but it is likely to push users to clear their old data or download new data from the server.
1 parent ee3f6ed commit 653c484

5 files changed

Lines changed: 51 additions & 5 deletions

File tree

libraries/AP_Terrain/AP_Terrain.cpp

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -57,8 +57,8 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = {
5757

5858
// @Param: OPTIONS
5959
// @DisplayName: Terrain options
60-
// @Description: Options to change behaviour of terrain system
61-
// @Bitmask: 0:Disable Download,1:Disable Disk
60+
// @Description: Options to change behavior of terrain system. The Accept Old Terrain Data option can be used to accept terrain data generated from before the terrain database bugs were fixed. The bugs in the data were all fixed from 24th February 2026. If you really want to risk using the old terrain data then you can set this option, otherwise remove the old terrain data by formatting your microSD card or renaming the /APM/TERRAIN folder. Then downloaded updated data from https://terrain.ardupilot.org, or let the automatic terrain download repopulate your terrain data.
61+
// @Bitmask: 0:Disable Download,1:Disable Disk,2:Accept Old Terrain Data
6262
// @User: Advanced
6363
AP_GROUPINFO("OPTIONS", 2, AP_Terrain, options, 0),
6464

@@ -449,6 +449,16 @@ bool AP_Terrain::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) cons
449449
return false;
450450
}
451451

452+
if (!option_set(Options::AcceptOldData) && found_old_data) {
453+
/*
454+
we have found old terrain data on the microSD card, warn the
455+
user that they have out of date terrain data that may
456+
contain errors.
457+
*/
458+
hal.util->snprintf(failure_msg, failure_msg_len, "terrain data expired, possible errors");
459+
return false;
460+
}
461+
452462
return true;
453463
}
454464

libraries/AP_Terrain/AP_Terrain.h

Lines changed: 17 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,10 @@
5353
// format of grid on disk
5454
#define TERRAIN_GRID_FORMAT_VERSION 1
5555

56+
// min minor version for data read from microSD
57+
// raise this to force a refresh of data from the terrain servers
58+
#define TERRAIN_VERSION_MINOR_MIN 1
59+
5660
// we allow for a 2cm discrepancy in the grid corners. This is to
5761
// account for different rounding in terrain DAT file generators using
5862
// different programming languages
@@ -242,6 +246,10 @@ class AP_Terrain {
242246
// rounded latitude/longitude in degrees.
243247
int16_t lon_degrees;
244248
int8_t lat_degrees;
249+
250+
// minor version. Note! this and any bytes after this are
251+
// excluded from the CRC for backwards compatibility
252+
uint8_t version_minor;
245253
};
246254

247255
/*
@@ -383,10 +391,15 @@ class AP_Terrain {
383391
enum class Options {
384392
DisableDownload = (1U<<0),
385393
DisableDisk = (1U<<1),
394+
AcceptOldData = (1U<<2),
386395
};
387396

397+
inline bool option_set(enum Options option) const {
398+
return (options.get() & uint16_t(option)) != 0;
399+
}
400+
388401
inline bool diskless() const {
389-
return (options.get() & uint16_t(Options::DisableDisk)) != 0;
402+
return option_set(Options::DisableDisk);
390403
}
391404

392405
// cache of grids in memory, LRU
@@ -482,6 +495,9 @@ class AP_Terrain {
482495
bool memory_alloc_failed;
483496

484497
static AP_Terrain *singleton;
498+
499+
// true if we have found old disk blocks when loading
500+
bool found_old_data;
485501
};
486502

487503
namespace AP {

libraries/AP_Terrain/TerrainGCS.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ bool AP_Terrain::request_missing(GCS_MAVLINK &link, struct grid_cache &gcache)
4444

4545
struct grid_block &grid = gcache.grid;
4646

47-
if (options.get() & uint16_t(Options::DisableDownload)) {
47+
if (option_set(Options::DisableDownload)) {
4848
return false;
4949
}
5050

libraries/AP_Terrain/TerrainIO.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include <AP_Common/AP_Common.h>
2626
#include <AP_Math/AP_Math.h>
2727
#include <stdio.h>
28+
#include <GCS_MAVLink/GCS.h>
2829

2930
extern const AP_HAL::HAL& hal;
3031

@@ -333,6 +334,19 @@ void AP_Terrain::read_block(void)
333334
(int)ret,
334335
(unsigned long long)disk_block.block.bitmap);
335336
#endif
337+
if (disk_block.block.version_minor < TERRAIN_VERSION_MINOR_MIN) {
338+
/*
339+
this triggers a pre-arm warning to prompt the user to
340+
download new terrain data
341+
*/
342+
#if HAL_GCS_ENABLED
343+
if (!found_old_data && hal.util->get_soft_armed()) {
344+
// in-flight warning for GCS operator
345+
gcs().send_text(MAV_SEVERITY_WARNING, "terrain data expired, possible errors");
346+
}
347+
#endif
348+
found_old_data = true;
349+
}
336350
}
337351
disk_io_state = DiskIoDoneRead;
338352
}

libraries/AP_Terrain/TerrainUtil.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -135,6 +135,7 @@ AP_Terrain::grid_cache &AP_Terrain::find_grid_cache(const struct grid_info &info
135135
grid.grid.lat_degrees = info.lat_degrees;
136136
grid.grid.lon_degrees = info.lon_degrees;
137137
grid.grid.version = TERRAIN_GRID_FORMAT_VERSION;
138+
grid.grid.version_minor = TERRAIN_VERSION_MINOR_MIN;
138139
grid.last_access_ms = now_ms;
139140

140141
// mark as waiting for disk read
@@ -173,7 +174,12 @@ uint16_t AP_Terrain::get_block_crc(struct grid_block &block)
173174
{
174175
uint16_t saved_crc = block.crc;
175176
block.crc = 0;
176-
uint16_t ret = crc16_ccitt((const uint8_t *)&block, sizeof(block), 0);
177+
/*
178+
note that we exclude version_minor and any later bytes from the
179+
CRC to maintain backwards compatibility so old versions of
180+
ArduPilot accept new terrain blocks
181+
*/
182+
uint16_t ret = crc16_ccitt((const uint8_t *)&block, offsetof(struct grid_block, version_minor), 0);
177183
block.crc = saved_crc;
178184
return ret;
179185
}

0 commit comments

Comments
 (0)