[451/678] Compiling libraries/AP_Terrain/TerrainIO.cpp
../../libraries/AP_Terrain/TerrainIO.cpp: In member function ‘void AP_Terrain::open_file()’:
../../libraries/AP_Terrain/TerrainIO.cpp:167:35: error: ‘.DAT’ directive output may be truncated writing 4 bytes into a region of size between 2 and 5 [-Werror=format-truncation=]
167 | snprintf(p, 13, "/%c%02u%c%03u.DAT",
| ^~~~
compilation terminated due to -Wfatal-errors.
this fixes several issues:
- allows users to download terrain data at home with no GPS lock
- allows for a TERRAIN_CHECK without GPS lock
- retries opening of files every 5 seconds to allow for remount of sd
card after boot
this fixes a problem where two different locations could both be
mapped to the same disk block in the terrain/*.DAT files. That meant
that pre-filled terrain on the microSD card would sometimes require a
download in flight. It also means that a RTL with loss of GCS could
sometimes fly through a region with no terrain data available
Other changes in this patch:
- allow for a 2cm discrepancy in the lat/lon of the grid
corners. This is needed to allow for slightly different floating
point rounding in tools that pre-generate terrain data to load on
the microSD
- added TERRAIN_OPTIONS parameter to allow the user to disable
attempts to download new terrain data. This is mostly useful for
testing to validate a terrain generator
See discussion here:
https://github.com/ArduPilot/ardupilot/issues/7331
we were getting some uninitialised variables. While it only showed up in
AP_SbusOut, it means we can't be sure it won't happen on other objects,
so safest to remove the approach
Thanks to assistance from Lucas, Peter and Francisco
../../libraries/AP_Terrain/TerrainIO.cpp: In member function ‘void
AP_Terrain::open_file()’:
../../libraries/AP_Terrain/TerrainIO.cpp:176:46: warning: format ‘%u’
expects argument of type ‘unsigned int’, but argument 5 has type
‘__gnu_cxx::__enable_if<true, double>::__type {aka double}’ [-Wformat=]
abs((uint32_t)block.lon_degrees));
^
../../libraries/AP_Terrain/TerrainIO.cpp:176:46: warning: format ‘%u’
expects argument of type ‘unsigned int’, but argument 7 has type
‘__gnu_cxx::__enable_if<true, double>::__type {aka double}’ [-Wformat=]
By opening with O_CLOEXEC we make sure we don't leak the file descriptor
when we are exec'ing or calling out subprograms. Right now we currently
don't do it so there's no harm, but it's good practice in Linux to have
it.
RC_Channel: To nullptr from NULL.
AC_Fence: To nullptr from NULL.
AC_Avoidance: To nullptr from NULL.
AC_PrecLand: To nullptr from NULL.
DataFlash: To nullptr from NULL.
SITL: To nullptr from NULL.
GCS_MAVLink: To nullptr from NULL.
DataFlash: To nullptr from NULL.
AP_Compass: To nullptr from NULL.
Global: To nullptr from NULL.
Global: To nullptr from NULL.