|
|
|
@ -93,7 +93,7 @@ public:
@@ -93,7 +93,7 @@ public:
|
|
|
|
|
void guidedModeRTL (Vehicle* vehicle, bool smartRTL) override; |
|
|
|
|
void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeChange) override; |
|
|
|
|
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override; |
|
|
|
|
void adjustOutgoingMavlinkMessage (Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message) override; |
|
|
|
|
void adjustOutgoingMavlinkMessageThreadSafe(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message) override; |
|
|
|
|
virtual void initializeStreamRates (Vehicle* vehicle); |
|
|
|
|
void initializeVehicle (Vehicle* vehicle) override; |
|
|
|
|
bool sendHomePositionToVehicle (void) override; |
|
|
|
@ -127,7 +127,7 @@ private:
@@ -127,7 +127,7 @@ private:
|
|
|
|
|
void _handleIncomingParamValue(Vehicle* vehicle, mavlink_message_t* message); |
|
|
|
|
bool _handleIncomingStatusText(Vehicle* vehicle, mavlink_message_t* message); |
|
|
|
|
void _handleIncomingHeartbeat(Vehicle* vehicle, mavlink_message_t* message); |
|
|
|
|
void _handleOutgoingParamSet(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message); |
|
|
|
|
void _handleOutgoingParamSetThreadSafe(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message); |
|
|
|
|
void _soloVideoHandshake(Vehicle* vehicle, bool originalSoloFirmware); |
|
|
|
|
bool _guidedModeTakeoff(Vehicle* vehicle, double altitudeRel); |
|
|
|
|
void _handleRCChannels(Vehicle* vehicle, mavlink_message_t* message); |
|
|
|
@ -141,6 +141,8 @@ private:
@@ -141,6 +141,8 @@ private:
|
|
|
|
|
QList<APMCustomMode> _supportedModes; |
|
|
|
|
QMap<int /* vehicle id */, QMap<int /* componentId */, bool /* true: component is part of ArduPilot stack */>> _ardupilotComponentMap; |
|
|
|
|
|
|
|
|
|
QMutex _adjustOutgoingMavlinkMutex; |
|
|
|
|
|
|
|
|
|
static const char* _artooIP; |
|
|
|
|
static const int _artooVideoHandshakePort; |
|
|
|
|
}; |
|
|
|
|