The squares surrounding the current location were only checked when we went to send a terrain request. This means it was possible that:
- the number of pending requests could go to zero
- prearm checks would pass
- vehicle arm is attempted by the user (or a script, or ....)
- the code would call AP_Terrain::send_requests which would create more pending requests
- the arming sequence would fail
It's also possible for the arming to succeed, and then we're flying in violation of the intended prearm checks.
Doing things in the update function has the additional advantage of making things more efficient as we can push out terrain requests more often.
looking at pending is insufficient as we may have more mission items to check to see if they need other pieces of terrain. That is, terr_pending can go to zero momentarily and then go back to a non-zero number as Terrain's update method checks the mission and rally libraries for more terrain requirements.
Without this patch the prearm checks can momentarily pass, allowing the vehicle to arm. The vehicle could hit a terrain failsafe later if it doesn't manage to get the data while in flight.
this restores the terrain adjustment functionality removed in #19946,
but without the problematic approach of always using home (which can
be moved in flight) and with a TERR_OFS_MAX parameter to limit the
amount of adjustment
Fixes:
../../libraries/AP_Terrain/TerrainGCS.cpp: In member function ‘void AP_Terrain::
handle_terrain_data(const mavlink_message_t&)’:
../../libraries/AP_Terrain/AP_Terrain.h:65:55: error: comparison between signed
and unsigned integer expressions [-Werror=sign-compare]
#define TERRAIN_LATLON_EQUAL(v1, v2) (labs((v1)-(v2)) <= unsigned(margin.get()*
100))
~~~~~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~
~~~~
../../libraries/AP_Terrain/AP_Terrain.h:65:55: note: in definition of macro ‘TER
RAIN_LATLON_EQUAL’
#define TERRAIN_LATLON_EQUAL(v1, v2) (labs((v1)-(v2)) <= unsigned(margin.get()*
100))
^~
compilation terminated due to -Wfatal-errors.
cc1plus: some warnings being treated as errors
In file included from ../../libraries/AP_Terrain/TerrainUtil.cpp:24:0:
../../libraries/AP_Terrain/TerrainUtil.cpp: In member function ‘AP_Terrain::grid
_cache& AP_Terrain::find_grid_cache(const AP_Terrain::grid_info&)’:
../../libraries/AP_Terrain/AP_Terrain.h:65:55: error: comparison between signed
and unsigned integer expressions [-Werror=sign-compare]
#define TERRAIN_LATLON_EQUAL(v1, v2) (labs((v1)-(v2)) <= unsigned(margin.get()*
100))
~~~~~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~
~~~~
The return value of labs is signed
this sets the acceptance margin for GCS generated terrain data. You
can raise this to allow old data generated with the less accurate
longitude scaling to be used
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
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.
instead of computing the terrain status on-demand, assign it in update() and cache the result. Then external tasks that check the status won't be doing terrain intensive calculations in their thread. All the calculations needed for the status were being performed in update already so this is an optimization.
This commit changes the way libraries headers are included in source files:
- If the header is in the same directory the source belongs to, so the
notation '#include ""' is used with the path relative to the directory
containing the source.
- If the header is outside the directory containing the source, then we use
the notation '#include <>' with the path relative to libraries folder.
Some of the advantages of such approach:
- Only one search path for libraries headers.
- OSs like Windows may have a better lookup time.
if we run out of terrain data then extrapolate using the last
available terrain height at the AHRS position. This can be used to
cope with GCS outages over long distances where the terrain data isn't
preloaded