Terrain Protocol
The Terrain Protocol provides a mechanism for a vehicle to get terrain information (tiles) from a ground station, and for a ground station to check the autopilot terrain cache for a tile at a particular location.
Support for this protocol is indicated by AUTOPILOT_VERSION.capabilities
by the MAV_PROTOCOL_CAPABILITY_TERRAIN flag.
A vehicle that supports this capability must also support terrain following in missions using the data. Note however that a vehicle may also support terrain handling in missions using a distance sensor, even if this protocol is not supported and capability flag is not set.
Message/Enum Summary
Message | Description |
---|---|
TERRAIN_REQUEST | Request from drone (to GCS) for terrain data. The message specifies a mask indicating what tiles are required, and the GCS responds by sending TERRAIN_DATA for each tile. The drone will also stream TERRAIN_REPORT messages to provide progress updates while it is waiting for data. |
TERRAIN_DATA | Terrain data from GCS for a particular tile (sent in response to a TERRAIN_REQUEST). The lat /lon and grid_spacing must be the same as the lat /lon from a TERRAIN_REQUEST. |
TERRAIN_REPORT | The drone will stream TERRAIN_REPORT to indicate progress of terrain download, and in response to a TERRAIN_CHECK. |
TERRAIN_CHECK | Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission. |
Sequences
Autopilot Terrain Map Request
The sequence for a drone to update its terrain altitude information is entirely driven by the drone, and is shown below.
In summary, the sequence is:
- Drone sends TERRAIN_REQUEST to the GCS to request a set of tiles (specified in a mask).
- The GCS responds by sending a TERRAIN_DATA for each tile set in the mask
- The drone also streams TERRAIN_REPORT messages back to the GCS indicating the current state of the download
TERRAIN_REPORT.pending
andTERRAIN_REPORT.loaded
indicate how many tiles are expected and have arrived, respectively.TERRAIN_REPORT.lat
,.lon
, .terrain_height
, while duplicated in other messages, are useful for debugging (a GCS can check its own internal terrain data against what the information).
- The drone must maintain its own record of what tiles have arrived/not arrived, and can re-request any that are missing using a further TERRAIN_REQUEST (with mask indicating just the missing tiles)
The diagram below shows the way the data is encoded within the TERRAIN_REQUEST and TERRAIN_DATA.
TERRAIN_REQUEST.mask is a 64-bit value that represents a row major 8x7 array of (4x4) tiles. The the lat
, lon
fields indicate the position of the South-West corner of first grid position (tile). The tiles are allocated sequentially in rows (West to East) starting from the lowest significant bit of mask
, and then in columns (South to North).
Each tile represents a 4x4 grid of altitude information. The spacing between the rows/columns in the tile is indicated by grid_spacing
(the same value must be used in both request and data messages).
GCS Terrain Tile Check
The sequence for a GCS to check the autopilot terrain cache at a particular location is shown below.
In summary, the sequence is:
- GCS sends TERRAIN_CHECK to the vehicle to request terrain information at a specific location.
- The drone responds with a TERRAIN_REPORT message containing the tile information it has for that location. If it does not have tile information for the specified location, then the request is ignored.
- GCS can verify that the terrain report matches a terrain check by comparing the latitude/longitude fields for both messages.
The protocol does not define how the ground station handles the case if no
TERRAIN_REPORT
is received (although it might resend the request after a timeout).