7#include <QtCore/QTimer>
14 , _terrainFactGroup(terrainFactGroup)
15 , _terrainDataSendTimer(new QTimer(this))
19 _terrainDataSendTimer->setSingleShot(
false);
20 _terrainDataSendTimer->setInterval(1000.0/12.0);
21 (void) connect(_terrainDataSendTimer, &QTimer::timeout,
this, &TerrainProtocolHandler::_sendNextTerrainData);
31 switch (message.msgid) {
32 case MAVLINK_MSG_ID_TERRAIN_REQUEST:
33 _handleTerrainRequest(message);
35 case MAVLINK_MSG_ID_TERRAIN_REPORT:
36 _handleTerrainReport(message);
43void TerrainProtocolHandler::_handleTerrainRequest(
const mavlink_message_t &message)
45 _terrainRequestActive =
true;
46 mavlink_msg_terrain_request_decode(&message, &_currentTerrainRequest);
47 _sendNextTerrainData();
50void TerrainProtocolHandler::_handleTerrainReport(
const mavlink_message_t &message)
52 mavlink_terrain_report_t terrainReport;
53 mavlink_msg_terrain_report_decode(&message, &terrainReport);
55 _terrainFactGroup->blocksPending()->setRawValue(terrainReport.pending);
56 _terrainFactGroup->blocksLoaded()->setRawValue(terrainReport.loaded);
58 if (TerrainProtocolHandlerLog().isDebugEnabled()) {
60 QList<double> altitudes;
61 QList<QGeoCoordinate> coordinates;
62 QGeoCoordinate coord(
static_cast<double>(terrainReport.lat) / 1e7,
static_cast<double>(terrainReport.lon) / 1e7);
63 (void) coordinates.append(coord);
65 const QString vehicleAlt = terrainReport.spacing ? QStringLiteral(
"%1").arg(terrainReport.terrain_height) : QStringLiteral(
"n/a");
68 qgcAlt = QStringLiteral(
"Error");
69 }
else if (altAvailable && !altitudes.isEmpty()) {
70 qgcAlt = QStringLiteral(
"%1").arg(altitudes[0]);
72 qgcAlt = QStringLiteral(
"N/A");
74 qCDebug(TerrainProtocolHandlerLog) <<
"TERRAIN_REPORT" << coord << QStringLiteral(
"Vehicle(%1) QGC(%2)").arg(vehicleAlt).arg(qgcAlt);
78void TerrainProtocolHandler::_sendNextTerrainData()
80 if (!_terrainRequestActive) {
84 QGeoCoordinate terrainRequestCoordSWCorner(
static_cast<double>(_currentTerrainRequest.lat) / 1e7,
static_cast<double>(_currentTerrainRequest.lon) / 1e7);
85 const int spacingBetweenGrids = _currentTerrainRequest.grid_spacing * 4;
91 bool bitFound =
false;
92 for (
int rowIndex=0; rowIndex<7; rowIndex++) {
93 for (
int colIndex=0; colIndex<8; colIndex++) {
94 const uint8_t gridBit = (rowIndex * 8) + colIndex;
95 const uint64_t checkBit = 1ull << gridBit;
96 if (_currentTerrainRequest.mask & checkBit) {
98 QGeoCoordinate swCorner = terrainRequestCoordSWCorner.atDistanceAndAzimuth(spacingBetweenGrids * colIndex, 90);
99 swCorner = swCorner.atDistanceAndAzimuth(spacingBetweenGrids * rowIndex, 0);
100 _sendTerrainData(swCorner, gridBit);
113 _terrainDataSendTimer->start();
115 _terrainRequestActive =
false;
119void TerrainProtocolHandler::_sendTerrainData(
const QGeoCoordinate &swCorner, uint8_t gridBit)
121 QList<QGeoCoordinate> coordinates;
122 for (
int rowIndex=0; rowIndex<4; rowIndex++) {
123 for (
int colIndex=0; colIndex<4; colIndex++) {
125 QGeoCoordinate coord = swCorner.atDistanceAndAzimuth(_currentTerrainRequest.grid_spacing * colIndex, 90);
126 coord = coord.atDistanceAndAzimuth(_currentTerrainRequest.grid_spacing * rowIndex, 0);
127 coordinates.append(coord);
133 QList<double> altitudes;
139 qCWarning(TerrainProtocolHandlerLog) << Q_FUNC_INFO <<
"TerrainAtCoordinateQuery::getAltitudesForCoordinates failed";
144 const uint64_t removeBit = ~(1ull << gridBit);
145 _currentTerrainRequest.mask &= removeBit;
147 int16_t terrainData[16];
148 for (
const double& altitude : altitudes) {
149 terrainData[altIndex++] =
static_cast<int16_t
>(altitude);
155 (void) mavlink_msg_terrain_data_pack_chan(
158 sharedLink->mavlinkChannel(),
160 _currentTerrainRequest.lat,
161 _currentTerrainRequest.lon,
162 _currentTerrainRequest.grid_spacing,
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static int getComponentId()
Get the component id of this application.
static MAVLinkProtocol * instance()
int getSystemId() const
Get the system id of this application.
static bool getAltitudesForCoordinates(const QList< QGeoCoordinate > &coordinates, QList< double > &altitudes, bool &error)
bool mavlinkMessageReceived(const mavlink_message_t &message)
~TerrainProtocolHandler()
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)