|
53 | 53 | // format of grid on disk |
54 | 54 | #define TERRAIN_GRID_FORMAT_VERSION 1 |
55 | 55 |
|
| 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 | + |
56 | 60 | // we allow for a 2cm discrepancy in the grid corners. This is to |
57 | 61 | // account for different rounding in terrain DAT file generators using |
58 | 62 | // different programming languages |
@@ -242,6 +246,10 @@ class AP_Terrain { |
242 | 246 | // rounded latitude/longitude in degrees. |
243 | 247 | int16_t lon_degrees; |
244 | 248 | 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; |
245 | 253 | }; |
246 | 254 |
|
247 | 255 | /* |
@@ -383,10 +391,15 @@ class AP_Terrain { |
383 | 391 | enum class Options { |
384 | 392 | DisableDownload = (1U<<0), |
385 | 393 | DisableDisk = (1U<<1), |
| 394 | + AcceptOldData = (1U<<2), |
386 | 395 | }; |
387 | 396 |
|
| 397 | + inline bool option_set(enum Options option) const { |
| 398 | + return (options.get() & uint16_t(option)) != 0; |
| 399 | + } |
| 400 | + |
388 | 401 | inline bool diskless() const { |
389 | | - return (options.get() & uint16_t(Options::DisableDisk)) != 0; |
| 402 | + return option_set(Options::DisableDisk); |
390 | 403 | } |
391 | 404 |
|
392 | 405 | // cache of grids in memory, LRU |
@@ -482,6 +495,9 @@ class AP_Terrain { |
482 | 495 | bool memory_alloc_failed; |
483 | 496 |
|
484 | 497 | static AP_Terrain *singleton; |
| 498 | + |
| 499 | + // true if we have found old disk blocks when loading |
| 500 | + bool found_old_data; |
485 | 501 | }; |
486 | 502 |
|
487 | 503 | namespace AP { |
|
0 commit comments