QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
TerrainQueryCoordinator.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QElapsedTimer>
4#include <QtCore/QList>
5#include <QtCore/QObject>
6#include <QtCore/QPointer>
7#include <QtPositioning/QGeoCoordinate>
8
9#include "MAVLinkEnums.h"
10
12class Vehicle;
13
27class TerrainQueryCoordinator : public QObject
28{
29 Q_OBJECT
30
31public:
32 explicit TerrainQueryCoordinator(Vehicle* vehicle);
33
36 void doSetHomeWithTerrain(const QGeoCoordinate& coord);
37
41 void roiWithTerrain(const QGeoCoordinate& coord);
42
45 void sendROICommand(const QGeoCoordinate& coord, MAV_FRAME frame, float altitude);
46
50
51private slots:
52 void _doSetHomeTerrainReceived(bool success, QList<double> heights);
53 void _roiTerrainReceived(bool success, QList<double> heights);
54 void _altitudeAboveTerrainReceived(bool success, QList<double> heights);
55
56private:
57 Vehicle* _vehicle = nullptr;
58
59 // QPointer: TerrainAtCoordinateQuery self-deletes after its signal (autoDelete=true).
60 QPointer<TerrainAtCoordinateQuery> _doSetHomeQuery;
61 QGeoCoordinate _doSetHomeCoordinate;
62
63 QPointer<TerrainAtCoordinateQuery> _roiQuery;
64 QGeoCoordinate _roiCoordinate;
65
66 QElapsedTimer _altQueryTimer;
67 QPointer<TerrainAtCoordinateQuery> _altQuery;
68 QGeoCoordinate _altLastCoord;
69 float _altLastRelAlt = qQNaN();
70};
NOTE: TerrainAtCoordinateQuery is not thread safe. All instances/calls to ElevationProvider must be o...
Coordinates the three terrain-query workflows attached to a Vehicle:
void roiWithTerrain(const QGeoCoordinate &coord)
void sendROICommand(const QGeoCoordinate &coord, MAV_FRAME frame, float altitude)
void doSetHomeWithTerrain(const QGeoCoordinate &coord)