|
QGroundControl
Ground Control Station for MAVLink Drones
|
Coordinates the three terrain-query workflows attached to a Vehicle: More...
#include <TerrainQueryCoordinator.h>
Inheritance diagram for TerrainQueryCoordinator:
Collaboration diagram for TerrainQueryCoordinator:Public Member Functions | |
| TerrainQueryCoordinator (Vehicle *vehicle) | |
| void | doSetHomeWithTerrain (const QGeoCoordinate &coord) |
| void | roiWithTerrain (const QGeoCoordinate &coord) |
| void | sendROICommand (const QGeoCoordinate &coord, MAV_FRAME frame, float altitude) |
| void | updateAltAboveTerrain () |
Coordinates the three terrain-query workflows attached to a Vehicle:
Each workflow owns a single outstanding TerrainAtCoordinateQuery; starting a new request while one is in-flight disconnects the previous one (auto-deleted by TerrainQuery). Callbacks access the Vehicle to send commands or write facts.
Definition at line 27 of file TerrainQueryCoordinator.h.
|
explicit |
Definition at line 23 of file TerrainQueryCoordinator.cc.
| void TerrainQueryCoordinator::doSetHomeWithTerrain | ( | const QGeoCoordinate & | coord | ) |
DO_SET_HOME terrain-backed flow. Starts a terrain query; when it resolves, sends MAV_CMD_DO_SET_HOME if the coordinate and resolved altitude are valid.
Definition at line 30 of file TerrainQueryCoordinator.cc.
References TerrainAtCoordinateQuery::terrainDataReceived().
Referenced by Vehicle::doSetHome().
| void TerrainQueryCoordinator::roiWithTerrain | ( | const QGeoCoordinate & | coord | ) |
PX4 ROI flow. Starts a terrain query; when it resolves, sends MAV_CMD_DO_SET_ROI_LOCATION in MAV_FRAME_GLOBAL at the resolved altitude (falling back to home altitude on query failure).
Definition at line 87 of file TerrainQueryCoordinator.cc.
References TerrainAtCoordinateQuery::terrainDataReceived().
Referenced by Vehicle::guidedModeROI().
| void TerrainQueryCoordinator::sendROICommand | ( | const QGeoCoordinate & | coord, |
| MAV_FRAME | frame, | ||
| float | altitude | ||
| ) |
Build + send MAV_CMD_DO_SET_ROI_LOCATION directly (no terrain query). Used by the ArduPilot MAV_FRAME_GLOBAL_RELATIVE_ALT direct path.
Definition at line 135 of file TerrainQueryCoordinator.cc.
References Vehicle::capabilityBits(), Vehicle::defaultComponentId(), Vehicle::sendMavCommand(), and Vehicle::sendMavCommandInt().
Referenced by Vehicle::guidedModeROI().
| void TerrainQueryCoordinator::updateAltAboveTerrain | ( | ) |
Periodic altitude-above-terrain query. Connected to Vehicle::coordinateChanged. Throttled by time (500 ms min) and distance/altitude deltas (2 m / 0.5 m).
Definition at line 165 of file TerrainQueryCoordinator.cc.
References VehicleFactGroup::altitudeRelative(), Vehicle::coordinate(), Fact::rawValue(), and TerrainAtCoordinateQuery::terrainDataReceived().