|
QGroundControl
Ground Control Station for MAVLink Drones
|
NOTE: TerrainAtCoordinateQuery is not thread safe. All instances/calls to ElevationProvider must be on main thread. More...
#include <TerrainQuery.h>
Inheritance diagram for TerrainAtCoordinateQuery:
Collaboration diagram for TerrainAtCoordinateQuery:Signals | |
| void | terrainDataReceived (bool success, const QList< double > &heights) |
Public Member Functions | |
| TerrainAtCoordinateQuery (bool autoDelete, QObject *parent=nullptr) | |
| ~TerrainAtCoordinateQuery () | |
| void | requestData (const QList< QGeoCoordinate > &coordinates) |
| void | signalTerrainData (bool success, const QList< double > &heights) |
Static Public Member Functions | |
| static bool | getAltitudesForCoordinates (const QList< QGeoCoordinate > &coordinates, QList< double > &altitudes, bool &error) |
NOTE: TerrainAtCoordinateQuery is not thread safe. All instances/calls to ElevationProvider must be on main thread.
Definition at line 74 of file TerrainQuery.h.
|
explicit |
| autoDelete | true: object will delete itself after it signals results |
Definition at line 161 of file TerrainQuery.cc.
| TerrainAtCoordinateQuery::~TerrainAtCoordinateQuery | ( | ) |
Definition at line 168 of file TerrainQuery.cc.
|
static |
Either returns altitudes from cache or queues database request
| [out] | error | true: altitude not returned due to error, false: altitudes returned |
Definition at line 182 of file TerrainQuery.cc.
References error, TerrainTileManager::getAltitudesForCoordinates(), and TerrainTileManager::instance().
| void TerrainAtCoordinateQuery::requestData | ( | const QList< QGeoCoordinate > & | coordinates | ) |
Async terrain query for a list of lon,lat coordinates. When the query is done, the terrainData() signal is emitted.
| coordinates | to query |
Definition at line 173 of file TerrainQuery.cc.
References TerrainAtCoordinateBatchManager::addQuery(), and TerrainAtCoordinateBatchManager::instance().
Referenced by Vehicle::doSetHome(), and Vehicle::guidedModeROI().
| void TerrainAtCoordinateQuery::signalTerrainData | ( | bool | success, |
| const QList< double > & | heights | ||
| ) |
Definition at line 187 of file TerrainQuery.cc.
References terrainDataReceived().
|
signal |
Referenced by Vehicle::doSetHome(), Vehicle::guidedModeROI(), and signalTerrainData().