QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
TerrainProtocolHandler.cc
Go to the documentation of this file.
2#include "TerrainQuery.h"
3#include "Vehicle.h"
4#include "MAVLinkProtocol.h"
6
7#include <QtCore/QTimer>
8
9QGC_LOGGING_CATEGORY(TerrainProtocolHandlerLog, "Vehicle.TerrainProtocolHandler")
10
11TerrainProtocolHandler::TerrainProtocolHandler(Vehicle *vehicle, TerrainFactGroup *terrainFactGroup, QObject *parent)
12 : QObject(parent)
13 , _vehicle(vehicle)
14 , _terrainFactGroup(terrainFactGroup)
15 , _terrainDataSendTimer(new QTimer(this))
16{
17 // qCDebug(TerrainProtocolHandlerLog) << Q_FUNC_INFO << this;
18
19 _terrainDataSendTimer->setSingleShot(false);
20 _terrainDataSendTimer->setInterval(1000.0/12.0);
21 (void) connect(_terrainDataSendTimer, &QTimer::timeout, this, &TerrainProtocolHandler::_sendNextTerrainData);
22}
23
25{
26 // qCDebug(TerrainProtocolHandlerLog) << Q_FUNC_INFO << this;
27}
28
30{
31 switch (message.msgid) {
32 case MAVLINK_MSG_ID_TERRAIN_REQUEST:
33 _handleTerrainRequest(message);
34 return false;
35 case MAVLINK_MSG_ID_TERRAIN_REPORT:
36 _handleTerrainReport(message);
37 return false;
38 default:
39 return true;
40 }
41}
42
43void TerrainProtocolHandler::_handleTerrainRequest(const mavlink_message_t &message)
44{
45 _terrainRequestActive = true;
46 mavlink_msg_terrain_request_decode(&message, &_currentTerrainRequest);
47 _sendNextTerrainData();
48}
49
50void TerrainProtocolHandler::_handleTerrainReport(const mavlink_message_t &message)
51{
52 mavlink_terrain_report_t terrainReport;
53 mavlink_msg_terrain_report_decode(&message, &terrainReport);
54
55 _terrainFactGroup->blocksPending()->setRawValue(terrainReport.pending);
56 _terrainFactGroup->blocksLoaded()->setRawValue(terrainReport.loaded);
57
58 if (TerrainProtocolHandlerLog().isDebugEnabled()) {
59 bool error;
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);
64 const bool altAvailable = TerrainAtCoordinateQuery::getAltitudesForCoordinates(coordinates, altitudes, error);
65 const QString vehicleAlt = terrainReport.spacing ? QStringLiteral("%1").arg(terrainReport.terrain_height) : QStringLiteral("n/a");
66 QString qgcAlt;
67 if (error) {
68 qgcAlt = QStringLiteral("Error");
69 } else if (altAvailable && !altitudes.isEmpty()) {
70 qgcAlt = QStringLiteral("%1").arg(altitudes[0]);
71 } else {
72 qgcAlt = QStringLiteral("N/A");
73 }
74 qCDebug(TerrainProtocolHandlerLog) << "TERRAIN_REPORT" << coord << QStringLiteral("Vehicle(%1) QGC(%2)").arg(vehicleAlt).arg(qgcAlt);
75 }
76}
77
78void TerrainProtocolHandler::_sendNextTerrainData()
79{
80 if (!_terrainRequestActive) {
81 return;
82 }
83
84 QGeoCoordinate terrainRequestCoordSWCorner(static_cast<double>(_currentTerrainRequest.lat) / 1e7, static_cast<double>(_currentTerrainRequest.lon) / 1e7);
85 const int spacingBetweenGrids = _currentTerrainRequest.grid_spacing * 4;
86
87 // Each TERRAIN_DATA sent to vehicle contains a 4x4 grid of heights
88 // TERRAIN_REQUEST.mask has a bit for each entry in an 8x7 grid
89 // gridBit = 0 refers to the the sw corner of the 8x7 grid
90
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) {
97 // Move east and then north to generate the coordinate for sw corner of the specific gridBit
98 QGeoCoordinate swCorner = terrainRequestCoordSWCorner.atDistanceAndAzimuth(spacingBetweenGrids * colIndex, 90);
99 swCorner = swCorner.atDistanceAndAzimuth(spacingBetweenGrids * rowIndex, 0);
100 _sendTerrainData(swCorner, gridBit);
101 bitFound = true;
102 break;
103 }
104 }
105
106 if (bitFound) {
107 break;
108 }
109 }
110
111 if (bitFound) {
112 // Kick timer to send next possible TERRAIN_DATA to vehicle
113 _terrainDataSendTimer->start();
114 } else {
115 _terrainRequestActive = false;
116 }
117}
118
119void TerrainProtocolHandler::_sendTerrainData(const QGeoCoordinate &swCorner, uint8_t gridBit)
120{
121 QList<QGeoCoordinate> coordinates;
122 for (int rowIndex=0; rowIndex<4; rowIndex++) {
123 for (int colIndex=0; colIndex<4; colIndex++) {
124 // Move east and then north to generate the coordinate for grid point
125 QGeoCoordinate coord = swCorner.atDistanceAndAzimuth(_currentTerrainRequest.grid_spacing * colIndex, 90);
126 coord = coord.atDistanceAndAzimuth(_currentTerrainRequest.grid_spacing * rowIndex, 0);
127 coordinates.append(coord);
128 }
129 }
130
131 // Query terrain system for altitudes. If it has them available it will return them. If not they will be queued for download.
132 bool error = false;
133 QList<double> altitudes;
134 if (!TerrainAtCoordinateQuery::getAltitudesForCoordinates(coordinates, altitudes, error)) {
135 return;
136 }
137
138 if (error) {
139 qCWarning(TerrainProtocolHandlerLog) << Q_FUNC_INFO << "TerrainAtCoordinateQuery::getAltitudesForCoordinates failed";
140 return;
141 }
142
143 // Only clear the bit if the query succeeds. Otherwise just let it try again on the next timer tick
144 const uint64_t removeBit = ~(1ull << gridBit);
145 _currentTerrainRequest.mask &= removeBit;
146 int altIndex = 0;
147 int16_t terrainData[16];
148 for (const double& altitude : altitudes) {
149 terrainData[altIndex++] = static_cast<int16_t>(altitude);
150 }
151
152 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
153 if (sharedLink) {
155 (void) mavlink_msg_terrain_data_pack_chan(
158 sharedLink->mavlinkChannel(),
159 &msg,
160 _currentTerrainRequest.lat,
161 _currentTerrainRequest.lon,
162 _currentTerrainRequest.grid_spacing,
163 gridBit,
164 terrainData
165 );
166
167 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
168 }
169}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
Error error
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)
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:580
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1470