Newer
Older
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include <QElapsedTimer>
#include "LinkInterface.h"
#include "QGCMAVLink.h"
#include "QmlObjectListModel.h"
#include "VehicleClockFactGroup.h"
#include "VehicleDistanceSensorFactGroup.h"
#include "VehicleWindFactGroup.h"
#include "VehicleGPSFactGroup.h"
#include "VehicleSetpointFactGroup.h"
#include "VehicleTemperatureFactGroup.h"
#include "VehicleVibrationFactGroup.h"
#include "VehicleEstimatorStatusFactGroup.h"
class UAS;
class UASInterface;
#if defined(QGC_AIRMAP_ENABLED)
class AirspaceVehicleManager;
#endif
Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
class Vehicle;
class Vehicle : public FactGroup
Vehicle(LinkInterface* link,
int vehicleId,
MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager,
JoystickManager* joystickManager);
// Pass these into the offline constructor to create an offline vehicle which tracks the offline vehicle settings
static const MAV_AUTOPILOT MAV_AUTOPILOT_TRACK = static_cast<MAV_AUTOPILOT>(-1);
static const MAV_TYPE MAV_TYPE_TRACK = static_cast<MAV_TYPE>(-1);
// The following is used to create a disconnected Vehicle for use while offline editing.
Vehicle(MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager,
/// Sensor bits from sensors*Bits properties
enum MavlinkSysStatus {
SysStatusSensor3dGyro = MAV_SYS_STATUS_SENSOR_3D_GYRO,
SysStatusSensor3dAccel = MAV_SYS_STATUS_SENSOR_3D_ACCEL,
SysStatusSensor3dMag = MAV_SYS_STATUS_SENSOR_3D_MAG,
SysStatusSensorAbsolutePressure = MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE,
SysStatusSensorDifferentialPressure = MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
SysStatusSensorGPS = MAV_SYS_STATUS_SENSOR_GPS,
SysStatusSensorOpticalFlow = MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW,
SysStatusSensorVisionPosition = MAV_SYS_STATUS_SENSOR_VISION_POSITION,
SysStatusSensorLaserPosition = MAV_SYS_STATUS_SENSOR_LASER_POSITION,
SysStatusSensorExternalGroundTruth = MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH,
SysStatusSensorAngularRateControl = MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL,
SysStatusSensorAttitudeStabilization = MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION,
SysStatusSensorYawPosition = MAV_SYS_STATUS_SENSOR_YAW_POSITION,
SysStatusSensorZAltitudeControl = MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL,
SysStatusSensorXYPositionControl = MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL,
SysStatusSensorMotorOutputs = MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS,
SysStatusSensorRCReceiver = MAV_SYS_STATUS_SENSOR_RC_RECEIVER,
SysStatusSensor3dGyro2 = MAV_SYS_STATUS_SENSOR_3D_GYRO2,
SysStatusSensor3dAccel2 = MAV_SYS_STATUS_SENSOR_3D_ACCEL2,
SysStatusSensor3dMag2 = MAV_SYS_STATUS_SENSOR_3D_MAG2,
SysStatusSensorGeoFence = MAV_SYS_STATUS_GEOFENCE,
SysStatusSensorAHRS = MAV_SYS_STATUS_AHRS,
SysStatusSensorTerrain = MAV_SYS_STATUS_TERRAIN,
SysStatusSensorReverseMotor = MAV_SYS_STATUS_REVERSE_MOTOR,
SysStatusSensorLogging = MAV_SYS_STATUS_LOGGING,
SysStatusSensorBattery = MAV_SYS_STATUS_SENSOR_BATTERY,
};
Q_ENUM(MavlinkSysStatus)
enum CheckList {
CheckListNotSetup = 0,
CheckListPassed,
CheckListFailed,
};
Q_ENUM(CheckList)
Q_PROPERTY(int id READ id CONSTANT)
Q_PROPERTY(AutoPilotPlugin* autopilot MEMBER _autopilotPlugin CONSTANT)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged)
Q_PROPERTY(QGeoCoordinate homePosition READ homePosition NOTIFY homePositionChanged)
Q_PROPERTY(QGeoCoordinate armedPosition READ armedPosition NOTIFY armedPositionChanged)
Q_PROPERTY(bool armed READ armed WRITE setArmed NOTIFY armedChanged)
Q_PROPERTY(bool autoDisarm READ autoDisarm NOTIFY autoDisarmChanged)
Q_PROPERTY(bool flightModeSetAvailable READ flightModeSetAvailable CONSTANT)
Q_PROPERTY(QStringList flightModes READ flightModes NOTIFY flightModesChanged)
Q_PROPERTY(QStringList extraJoystickFlightModes READ extraJoystickFlightModes NOTIFY flightModesChanged)
Q_PROPERTY(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged)
Q_PROPERTY(TrajectoryPoints* trajectoryPoints MEMBER _trajectoryPoints CONSTANT)
Q_PROPERTY(QmlObjectListModel* cameraTriggerPoints READ cameraTriggerPoints CONSTANT)
Q_PROPERTY(float latitude READ latitude NOTIFY coordinateChanged)
Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged)
Q_PROPERTY(bool messageTypeNone READ messageTypeNone NOTIFY messageTypeChanged)
Q_PROPERTY(bool messageTypeNormal READ messageTypeNormal NOTIFY messageTypeChanged)
Q_PROPERTY(bool messageTypeWarning READ messageTypeWarning NOTIFY messageTypeChanged)
Q_PROPERTY(bool messageTypeError READ messageTypeError NOTIFY messageTypeChanged)
Q_PROPERTY(int newMessageCount READ newMessageCount NOTIFY newMessageCountChanged)
Q_PROPERTY(int messageCount READ messageCount NOTIFY messageCountChanged)
Q_PROPERTY(QString formatedMessages READ formatedMessages NOTIFY formatedMessagesChanged)
Q_PROPERTY(QString formatedMessage READ formatedMessage NOTIFY formatedMessageChanged)
Q_PROPERTY(QString latestError READ latestError NOTIFY latestErrorChanged)
Q_PROPERTY(bool joystickEnabled READ joystickEnabled WRITE setJoystickEnabled NOTIFY joystickEnabledChanged)
Q_PROPERTY(bool active READ active WRITE setActive NOTIFY activeChanged)
Q_PROPERTY(int flowImageIndex READ flowImageIndex NOTIFY flowImageIndexChanged)
Q_PROPERTY(int rcRSSI READ rcRSSI NOTIFY rcRSSIChanged)
Q_PROPERTY(bool px4Firmware READ px4Firmware NOTIFY firmwareTypeChanged)
Q_PROPERTY(bool apmFirmware READ apmFirmware NOTIFY firmwareTypeChanged)
Q_PROPERTY(bool soloFirmware READ soloFirmware WRITE setSoloFirmware NOTIFY soloFirmwareChanged)
Q_PROPERTY(bool genericFirmware READ genericFirmware CONSTANT)
Q_PROPERTY(bool connectionLost READ connectionLost NOTIFY connectionLostChanged)
Q_PROPERTY(bool connectionLostEnabled READ connectionLostEnabled WRITE setConnectionLostEnabled NOTIFY connectionLostEnabledChanged)
Q_PROPERTY(uint messagesReceived READ messagesReceived NOTIFY messagesReceivedChanged)
Q_PROPERTY(uint messagesSent READ messagesSent NOTIFY messagesSentChanged)
Q_PROPERTY(uint messagesLost READ messagesLost NOTIFY messagesLostChanged)
Q_PROPERTY(bool fixedWing READ fixedWing NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool multiRotor READ multiRotor NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool vtol READ vtol NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool rover READ rover NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool sub READ sub NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool supportsThrottleModeCenterZero READ supportsThrottleModeCenterZero CONSTANT)
Q_PROPERTY(bool supportsNegativeThrust READ supportsNegativeThrust CONSTANT)
Q_PROPERTY(bool supportsJSButton READ supportsJSButton CONSTANT)
Q_PROPERTY(bool supportsRadio READ supportsRadio CONSTANT)
Q_PROPERTY(bool supportsMotorInterference READ supportsMotorInterference CONSTANT)
Q_PROPERTY(bool autoDisconnect MEMBER _autoDisconnect NOTIFY autoDisconnectChanged)
Q_PROPERTY(QString prearmError READ prearmError WRITE setPrearmError NOTIFY prearmErrorChanged)
Q_PROPERTY(int motorCount READ motorCount CONSTANT)
Q_PROPERTY(bool coaxialMotors READ coaxialMotors CONSTANT)
Q_PROPERTY(bool xConfigMotors READ xConfigMotors CONSTANT)
Q_PROPERTY(bool isOfflineEditingVehicle READ isOfflineEditingVehicle CONSTANT)
Q_PROPERTY(QString brandImageIndoor READ brandImageIndoor NOTIFY firmwareTypeChanged)
Q_PROPERTY(QString brandImageOutdoor READ brandImageOutdoor NOTIFY firmwareTypeChanged)
Q_PROPERTY(int sensorsPresentBits READ sensorsPresentBits NOTIFY sensorsPresentBitsChanged)
Q_PROPERTY(int sensorsEnabledBits READ sensorsEnabledBits NOTIFY sensorsEnabledBitsChanged)
Q_PROPERTY(int sensorsHealthBits READ sensorsHealthBits NOTIFY sensorsHealthBitsChanged)
Q_PROPERTY(int sensorsUnhealthyBits READ sensorsUnhealthyBits NOTIFY sensorsUnhealthyBitsChanged) ///< Combination of enabled and health
Q_PROPERTY(QString missionFlightMode READ missionFlightMode CONSTANT)
Q_PROPERTY(QString pauseFlightMode READ pauseFlightMode CONSTANT)
Q_PROPERTY(QString rtlFlightMode READ rtlFlightMode CONSTANT)
Q_PROPERTY(QString smartRTLFlightMode READ smartRTLFlightMode CONSTANT)
Q_PROPERTY(bool supportsSmartRTL READ supportsSmartRTL CONSTANT)
Q_PROPERTY(QString landFlightMode READ landFlightMode CONSTANT)
Q_PROPERTY(QString takeControlFlightMode READ takeControlFlightMode CONSTANT)
Q_PROPERTY(QString firmwareTypeString READ firmwareTypeString NOTIFY firmwareTypeChanged)
Q_PROPERTY(QString vehicleTypeString READ vehicleTypeString NOTIFY vehicleTypeChanged)
Q_PROPERTY(QString vehicleImageOpaque READ vehicleImageOpaque CONSTANT)
Q_PROPERTY(QString vehicleImageOutline READ vehicleImageOutline CONSTANT)
Q_PROPERTY(QString vehicleImageCompass READ vehicleImageCompass CONSTANT)
Q_PROPERTY(int telemetryRRSSI READ telemetryRRSSI NOTIFY telemetryRRSSIChanged)
Q_PROPERTY(int telemetryLRSSI READ telemetryLRSSI NOTIFY telemetryLRSSIChanged)
Q_PROPERTY(unsigned int telemetryRXErrors READ telemetryRXErrors NOTIFY telemetryRXErrorsChanged)
Q_PROPERTY(unsigned int telemetryFixed READ telemetryFixed NOTIFY telemetryFixedChanged)
Q_PROPERTY(unsigned int telemetryTXBuffer READ telemetryTXBuffer NOTIFY telemetryTXBufferChanged)
Q_PROPERTY(int telemetryLNoise READ telemetryLNoise NOTIFY telemetryLNoiseChanged)
Q_PROPERTY(int telemetryRNoise READ telemetryRNoise NOTIFY telemetryRNoiseChanged)
Q_PROPERTY(QVariantList toolIndicators READ toolIndicators NOTIFY toolIndicatorsChanged)
Q_PROPERTY(QVariantList modeIndicators READ modeIndicators NOTIFY modeIndicatorsChanged)
Q_PROPERTY(bool initialPlanRequestComplete READ initialPlanRequestComplete NOTIFY initialPlanRequestCompleteChanged)
Q_PROPERTY(QVariantList staticCameraList READ staticCameraList CONSTANT)
Q_PROPERTY(QGCCameraManager* cameraManager READ cameraManager NOTIFY cameraManagerChanged)
Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged)
Q_PROPERTY(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged)
Q_PROPERTY(bool highLatencyLink READ highLatencyLink NOTIFY highLatencyLinkChanged)
Q_PROPERTY(bool supportsTerrainFrame READ supportsTerrainFrame NOTIFY firmwareTypeChanged)
Q_PROPERTY(QString priorityLinkName READ priorityLinkName WRITE setPriorityLinkByName NOTIFY priorityLinkNameChanged)
Q_PROPERTY(QVariantList links READ links NOTIFY linksChanged)
Q_PROPERTY(LinkInterface* priorityLink READ priorityLink NOTIFY priorityLinkNameChanged)
Q_PROPERTY(quint64 mavlinkSentCount READ mavlinkSentCount NOTIFY mavlinkStatusChanged)
Q_PROPERTY(quint64 mavlinkReceivedCount READ mavlinkReceivedCount NOTIFY mavlinkStatusChanged)
Q_PROPERTY(quint64 mavlinkLossCount READ mavlinkLossCount NOTIFY mavlinkStatusChanged)
Q_PROPERTY(float mavlinkLossPercent READ mavlinkLossPercent NOTIFY mavlinkStatusChanged)
Q_PROPERTY(qreal gimbalRoll READ gimbalRoll NOTIFY gimbalRollChanged)
Q_PROPERTY(qreal gimbalPitch READ gimbalPitch NOTIFY gimbalPitchChanged)
Q_PROPERTY(qreal gimbalYaw READ gimbalYaw NOTIFY gimbalYawChanged)
Q_PROPERTY(bool gimbalData READ gimbalData NOTIFY gimbalDataChanged)
Q_PROPERTY(bool iARDURsROIEnabled READ isROIEnabled NOTIFY isROIEnabledChanged)
Q_PROPERTY(CheckList checkListState READ checkListState WRITE setCheckListState NOTIFY checkListStateChanged)
Q_PROPERTY(bool readyToFlyAvailable READ readyToFlyAvailable NOTIFY readyToFlyAvailableChanged) ///< true: readyToFly signalling is available on this vehicle
Q_PROPERTY(bool readyToFly READ readyToFly NOTIFY readyToFlyChanged)
Q_PROPERTY(QObject* sysStatusSensorInfo READ sysStatusSensorInfo CONSTANT)
Q_PROPERTY(bool allSensorsHealthy READ allSensorsHealthy NOTIFY allSensorsHealthyChanged) //< true: all sensors in SYS_STATUS reported as healthy
// The following properties relate to Orbit status
Q_PROPERTY(bool orbitActive READ orbitActive NOTIFY orbitActiveChanged)
Q_PROPERTY(QGCMapCircle* orbitMapCircle READ orbitMapCircle CONSTANT)
// Vehicle state used for guided control
Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying
Q_PROPERTY(bool landing READ landing NOTIFY landingChanged) ///< Vehicle is in landing pattern (DO_LAND_START)
Q_PROPERTY(bool guidedMode READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged) ///< Vehicle is in Guided mode and can respond to guided commands
Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT) ///< Guided mode commands are supported by this vehicle
Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT) ///< Pause vehicle command is supported
Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle
Q_PROPERTY(bool roiModeSupported READ roiModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle
Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported
Q_PROPERTY(QString gotoFlightMode READ gotoFlightMode CONSTANT) ///< Flight mode vehicle is in while performing goto
Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)
Q_PROPERTY(VehicleObjectAvoidance* objectAvoidance READ objectAvoidance CONSTANT)
// FactGroup object model properties
Q_PROPERTY(Fact* roll READ roll CONSTANT)
Q_PROPERTY(Fact* pitch READ pitch CONSTANT)
Q_PROPERTY(Fact* heading READ heading CONSTANT)
Q_PROPERTY(Fact* rollRate READ rollRate CONSTANT)
Q_PROPERTY(Fact* pitchRate READ pitchRate CONSTANT)
Q_PROPERTY(Fact* yawRate READ yawRate CONSTANT)
Q_PROPERTY(Fact* groundSpeed READ groundSpeed CONSTANT)
Q_PROPERTY(Fact* airSpeed READ airSpeed CONSTANT)
Q_PROPERTY(Fact* climbRate READ climbRate CONSTANT)
Q_PROPERTY(Fact* altitudeRelative READ altitudeRelative CONSTANT)
Q_PROPERTY(Fact* altitudeAMSL READ altitudeAMSL CONSTANT)
Q_PROPERTY(Fact* flightDistance READ flightDistance CONSTANT)
Q_PROPERTY(Fact* distanceToHome READ distanceToHome CONSTANT)
Q_PROPERTY(Fact* missionItemIndex READ missionItemIndex CONSTANT)
Q_PROPERTY(Fact* headingToNextWP READ headingToNextWP CONSTANT)
Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT)
Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT)
Q_PROPERTY(FactGroup* clock READ clockFactGroup CONSTANT)
Q_PROPERTY(FactGroup* setpoint READ setpointFactGroup CONSTANT)
Q_PROPERTY(FactGroup* estimatorStatus READ estimatorStatusFactGroup CONSTANT)
Q_PROPERTY(FactGroup* terrain READ terrainFactGroup CONSTANT)
Q_PROPERTY(FactGroup* distanceSensors READ distanceSensorFactGroup CONSTANT)
Q_PROPERTY(QmlObjectListModel* batteries READ batteries CONSTANT)
Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareVersionChanged)
Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareVersionChanged)
Q_PROPERTY(int firmwarePatchVersion READ firmwarePatchVersion NOTIFY firmwareVersionChanged)
Q_PROPERTY(int firmwareVersionType READ firmwareVersionType NOTIFY firmwareVersionChanged)
Q_PROPERTY(QString firmwareVersionTypeString READ firmwareVersionTypeString NOTIFY firmwareVersionChanged)
Q_PROPERTY(int firmwareCustomMajorVersion READ firmwareCustomMajorVersion NOTIFY firmwareCustomVersionChanged)
Q_PROPERTY(int firmwareCustomMinorVersion READ firmwareCustomMinorVersion NOTIFY firmwareCustomVersionChanged)
Q_PROPERTY(int firmwareCustomPatchVersion READ firmwareCustomPatchVersion NOTIFY firmwareCustomVersionChanged)
Q_PROPERTY(QString gitHash READ gitHash NOTIFY gitHashChanged)
Q_PROPERTY(quint64 vehicleUID READ vehicleUID NOTIFY vehicleUIDChanged)
Q_PROPERTY(QString vehicleUIDStr READ vehicleUIDStr NOTIFY vehicleUIDChanged)
/// Resets link status counters
Q_INVOKABLE void resetCounters ();
// Called when the message drop-down is invoked to clear current count
Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Q_INVOKABLE void disconnectInactiveVehicle();
/// Command vehicle to takeoff from current location
Q_INVOKABLE void guidedModeTakeoff(double altitudeRelative);
/// @return The minimum takeoff altitude (relative) for guided takeoff.
Q_INVOKABLE double minimumTakeoffAltitude();
/// Command vehicle to move to specified location (altitude is included and relative)
Q_INVOKABLE void guidedModeGotoLocation(const QGeoCoordinate& gotoCoord);
/// Command vehicle to change altitude
/// @param altitudeChange If > 0, go up by amount specified, if < 0, go down by amount specified
Q_INVOKABLE void guidedModeChangeAltitude(double altitudeChange);
/// Command vehicle to orbit given center point
/// @param radius Distance from vehicle to centerCoord
/// @param amslAltitude Desired vehicle altitude
Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude);
/// Command vehicle to keep given point as ROI
/// @param centerCoord ROI coordinates
Q_INVOKABLE void guidedModeROI(const QGeoCoordinate& centerCoord);
Q_INVOKABLE void stopGuidedModeROI();
/// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
/// in guided mode after pause.
/// Command vehicle to kill all motors no matter what state
/// Command vehicle to abort landing
Danny Schrader
committed
Q_INVOKABLE void abortLanding(double climbOutAltitude);
/// Alter the current mission item on the vehicle
Q_INVOKABLE void setCurrentMissionSequence(int seq);
/// Reboot vehicle
Q_INVOKABLE void rebootVehicle();
/// Clear Messages
Q_INVOKABLE void clearMessages();
/// Used to check if running current version is equal or higher than the one being compared.
// returns 1 if current > compare, 0 if current == compare, -1 if current < compare
Q_INVOKABLE int versionCompare(QString& compare);
Q_INVOKABLE int versionCompare(int major, int minor, int patch);
/// Test motor
/// @param motor Motor number, 1-based
/// @param percent 0-no power, 100-full power
/// @param timeoutSec Disabled motor after this amount of time
Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs);
Q_INVOKABLE void gimbalControlValue (double pitch, double yaw);
Q_INVOKABLE void gimbalPitchStep (int direction);
Q_INVOKABLE void gimbalYawStep (int direction);
Q_INVOKABLE void centerGimbal ();
/// Sends PARAM_MAP_RC message to vehicle
Q_INVOKABLE void sendParamMapRC(const QString& paramName, double scale, double centerValue, int tuningID, double minValue, double maxValue);
/// Clears all PARAM_MAP_RC settings from vehicle
Q_INVOKABLE void clearAllParamMapRC(void);
Q_INVOKABLE void flashBootloader();
bool guidedModeSupported () const;
bool pauseVehicleSupported () const;
bool orbitModeSupported () const;
bool roiModeSupported () const;
bool takeoffVehicleSupported () const;
QString gotoFlightMode () const;
// Property accessors
QGeoCoordinate coordinate() { return _coordinate; }
QGeoCoordinate armedPosition () { return _armedPosition; }
bool joystickEnabled ();
void setJoystickEnabled (bool enabled);
void sendJoystickDataThreadSafe (float roll, float pitch, float yaw, float thrust, quint16 buttons);
// Is vehicle active with respect to current active vehicle in QGC
int id() { return _id; }
MAV_AUTOPILOT firmwareType() const { return _firmwareType; }
MAV_TYPE vehicleType() const { return _vehicleType; }
Q_INVOKABLE QString vehicleTypeName() const;
/// Returns the highest quality link available to the Vehicle. If you need to hold a reference to this link use
/// LinkManager::sharedLinkInterfaceForGet to get QSharedPointer for link.
LinkInterface* priorityLink() { return _priorityLink.data(); }
/// Sends a message to the specified link
/// @return true: message sent, false: Link no longer connected
bool sendMessageOnLinkThreadSafe(LinkInterface* link, mavlink_message_t message);
/// Sends the specified messages multiple times to the vehicle in order to attempt to
/// guarantee that it makes it to the vehicle.
void sendMessageMultiple(mavlink_message_t message);
/// Provides access to uas from vehicle. Temporary workaround until UAS is fully phased out.
/// Provides access to uas from vehicle. Temporary workaround until AutoPilotPlugin is fully phased out.
AutoPilotPlugin* autopilotPlugin() { return _autopilotPlugin; }
/// Provides access to the Firmware Plugin for this Vehicle
FirmwarePlugin* firmwarePlugin() { return _firmwarePlugin; }
MissionManager* missionManager() { return _missionManager; }
GeoFenceManager* geoFenceManager() { return _geoFenceManager; }
RallyPointManager* rallyPointManager() { return _rallyPointManager; }
bool armed () { return _armed; }
void setArmed (bool armed);
bool flightModeSetAvailable ();
QStringList flightModes ();
QStringList extraJoystickFlightModes ();
QString flightMode () const;
QString priorityLinkName() const;
QVariantList links() const;
void setPriorityLinkByName(const QString& priorityLinkName);
bool fixedWing() const;
bool multiRotor() const;
bool vtol() const;
bool rover() const;
bool sub() const;
bool supportsThrottleModeCenterZero () const;
bool supportsNegativeThrust ();
bool supportsRadio () const;
bool supportsJSButton () const;
bool supportsMotorInterference () const;
bool supportsTerrainFrame () const;
QString prearmError() const { return _prearmError; }
void setPrearmError(const QString& prearmError);
QmlObjectListModel* cameraTriggerPoints () { return &_cameraTriggerPoints; }
int flowImageIndex() { return _flowImageIndex; }
//-- Mavlink Logging
void startMavlinkLog();
void stopMavlinkLog();
/// Requests the specified data stream from the vehicle
/// @param stream Stream which is being requested
/// @param rate Rate at which to send stream in Hz
/// @param sendMultiple Send multiple time to guarantee Vehicle reception
void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple = true);
// The follow method are used to turn on/off the tracking of settings updates for firmware/vehicle type on offline vehicles.
void trackFirmwareVehicleTypeChanges(void);
void stopTrackingFirmwareVehicleTypeChanges(void);
typedef enum {
MessageNone,
MessageNormal,
MessageWarning,
MessageError
} MessageType_t;
bool messageTypeNone () { return _currentMessageType == MessageNone; }
bool messageTypeNormal () { return _currentMessageType == MessageNormal; }
bool messageTypeWarning () { return _currentMessageType == MessageWarning; }
bool messageTypeError () { return _currentMessageType == MessageError; }
int newMessageCount () { return _currentMessageCount; }
int messageCount () { return _messageCount; }
QString formatedMessages ();
QString formatedMessage () { return _formatedMessage; }
QString latestError () { return _latestError; }
float latitude () { return static_cast<float>(_coordinate.latitude()); }
float longitude () { return static_cast<float>(_coordinate.longitude()); }
bool mavPresent () { return _mav != nullptr; }
int rcRSSI () { return _rcRSSI; }
bool px4Firmware () const { return _firmwareType == MAV_AUTOPILOT_PX4; }
bool apmFirmware () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
bool genericFirmware () const { return !px4Firmware() && !apmFirmware(); }
bool connectionLost () const { return _connectionLost; }
bool connectionLostEnabled () const { return _connectionLostEnabled; }
uint messagesReceived () { return _messagesReceived; }
uint messagesSent () { return _messagesSent; }
uint messagesLost () { return _messagesLost; }
bool flying () const { return _flying; }
bool landing () const { return _landing; }
bool vtolInFwdFlight () const { return _vtolInFwdFlight; }
uint8_t baseMode () const { return _base_mode; }
uint32_t customMode () const { return _custom_mode; }
bool isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
QString brandImageIndoor () const;
QString brandImageOutdoor () const;
int sensorsPresentBits () const { return static_cast<int>(_onboardControlSensorsPresent); }
int sensorsEnabledBits () const { return static_cast<int>(_onboardControlSensorsEnabled); }
int sensorsHealthBits () const { return static_cast<int>(_onboardControlSensorsHealth); }
int sensorsUnhealthyBits () const { return static_cast<int>(_onboardControlSensorsUnhealthy); }
QString missionFlightMode () const;
QString takeControlFlightMode () const;
double defaultCruiseSpeed () const { return _defaultCruiseSpeed; }
double defaultHoverSpeed () const { return _defaultHoverSpeed; }
QString firmwareTypeString () const;
QString vehicleTypeString () const;
int telemetryRRSSI () { return _telemetryRRSSI; }
int telemetryLRSSI () { return _telemetryLRSSI; }
unsigned int telemetryRXErrors () { return _telemetryRXErrors; }
unsigned int telemetryFixed () { return _telemetryFixed; }
unsigned int telemetryTXBuffer () { return _telemetryTXBuffer; }
int telemetryLNoise () { return _telemetryLNoise; }
int telemetryRNoise () { return _telemetryRNoise; }
bool highLatencyLink () const { return _highLatencyLink; }
bool orbitActive () const { return _orbitActive; }
QGCMapCircle* orbitMapCircle () { return &_orbitMapCircle; }
bool readyToFlyAvailable () { return _readyToFlyAvailable; }
bool readyToFly () { return _readyToFly; }
bool allSensorsHealthy () { return _allSensorsHealthy; }
QObject* sysStatusSensorInfo () { return &_sysStatusSensorInfo; }
/// Get the maximum MAVLink protocol version supported
/// @return the maximum version
unsigned maxProtoVersion () const { return _maxProtoVersion; }
enum CalibrationType {
CalibrationRadio,
CalibrationGyro,
CalibrationMag,
CalibrationAccel,
CalibrationLevel,
CalibrationEsc,
CalibrationCopyTrims,
CalibrationAPMCompassMot,
CalibrationAPMPressureAirspeed,
CalibrationAPMPreFlight,
CalibrationPX4Airspeed,
CalibrationPX4Pressure,
};
void startCalibration (CalibrationType calType);
void stopCalibration (void);
Fact* roll () { return &_rollFact; }
Fact* pitch () { return &_pitchFact; }
Fact* heading () { return &_headingFact; }
Fact* rollRate () { return &_rollRateFact; }
Fact* pitchRate () { return &_pitchRateFact; }
Fact* yawRate () { return &_yawRateFact; }
Fact* airSpeed () { return &_airSpeedFact; }
Fact* groundSpeed () { return &_groundSpeedFact; }
Fact* climbRate () { return &_climbRateFact; }
Fact* altitudeRelative () { return &_altitudeRelativeFact; }
Fact* altitudeAMSL () { return &_altitudeAMSLFact; }
Fact* flightDistance () { return &_flightDistanceFact; }
Fact* distanceToHome () { return &_distanceToHomeFact; }
Fact* missionItemIndex () { return &_missionItemIndexFact; }
Fact* headingToNextWP () { return &_headingToNextWPFact; }
Fact* headingToHome () { return &_headingToHomeFact; }
Fact* distanceToGCS () { return &_distanceToGCSFact; }
Fact* hobbs () { return &_hobbsFact; }
Fact* throttlePct () { return &_throttlePctFact; }
FactGroup* gpsFactGroup () { return &_gpsFactGroup; }
FactGroup* windFactGroup () { return &_windFactGroup; }
FactGroup* vibrationFactGroup () { return &_vibrationFactGroup; }
FactGroup* temperatureFactGroup () { return &_temperatureFactGroup; }
FactGroup* clockFactGroup () { return &_clockFactGroup; }
FactGroup* setpointFactGroup () { return &_setpointFactGroup; }
FactGroup* distanceSensorFactGroup () { return &_distanceSensorFactGroup; }
FactGroup* estimatorStatusFactGroup () { return &_estimatorStatusFactGroup; }
void setConnectionLostEnabled(bool connectionLostEnabled);
ParameterManager* parameterManager () { return _parameterManager; }
ParameterManager* parameterManager () const { return _parameterManager; }
FTPManager* ftpManager () { return _ftpManager; }
ComponentInformationManager* compInfoManager () { return _componentInformationManager; }
bool containsLink(LinkInterface* link) { return _links.contains(link); }
/// Sends the specified MAV_CMD to the vehicle. If no Ack is received command will be retried. If a sendMavCommand is already in progress
/// the command will be queued and sent when the previous command completes.
/// @param command MAV_CMD to send
/// @param showError true: Display error to user if command failed, false: no error shown
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
void sendMavCommandInt(int compId, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7);
/// Same as sendMavCommand but available from Qml.
Q_INVOKABLE void sendCommand(int compId, int command, bool showError, double param1 = 0.0, double param2 = 0.0, double param3 = 0.0, double param4 = 0.0, double param5 = 0.0, double param6 = 0.0, double param7 = 0.0)
showError,
static_cast<float>(param1),
static_cast<float>(param2),
static_cast<float>(param3),
static_cast<float>(param4),
static_cast<float>(param5),
static_cast<float>(param6),
static_cast<float>(param7));
}
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
/// Callback for sendMavCommandWithHandle
/// @param resultHandleData Opaque data passed in to sendMavCommand call
/// @param commandResult Ack result for command send
/// @param noReponseFromVehicle true: The vehicle did not responsed to the COMMAND_LONG message
typedef void (*MavCmdResultHandler)(void* resultHandlerData, int compId, MAV_RESULT commandResult, bool noResponsefromVehicle);
/// Sends the command and calls the callback with the result
/// @param resultHandler Callback for result, nullptr for no callback
/// @param resultHandleData Opaque data passed through callback
void sendMavCommandWithHandler(MavCmdResultHandler resultHandler, void* resultHandlerData, int compId, MAV_CMD command, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
typedef enum {
RequestMessageNoFailure,
RequestMessageFailureCommandError,
RequestMessageFailureCommandNotAcked,
RequestMessageFailureMessageNotReceived,
} RequestMessageResultHandlerFailureCode_t;
/// Callback for requestMessage
/// @param resultHandlerData Opaque data which was passed in to requestMessage call
/// @param commandResult Result from ack to REQUEST_MESSAGE command
/// @param noResponseToCommand true: Vehicle never acked the REQUEST_MESSAGE command
/// @param messageNotReceived true: Vehicle never sent requested message
typedef void (*RequestMessageResultHandler)(void* resultHandlerData, MAV_RESULT commandResult, RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t& message);
/// Requests the vehicle to send the specified message. Will retry a number of times.
/// @param resultHandler Callback for result
/// @param resultHandlerData Opaque data passed back to resultHandler
void requestMessage(RequestMessageResultHandler resultHandler, void* resultHandlerData, int compId, int messageId, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f);
int firmwareMajorVersion() const { return _firmwareMajorVersion; }
int firmwareMinorVersion() const { return _firmwareMinorVersion; }
int firmwarePatchVersion() const { return _firmwarePatchVersion; }
int firmwareVersionType() const { return _firmwareVersionType; }
int firmwareCustomMajorVersion() const { return _firmwareCustomMajorVersion; }
int firmwareCustomMinorVersion() const { return _firmwareCustomMinorVersion; }
int firmwareCustomPatchVersion() const { return _firmwareCustomPatchVersion; }
QString firmwareVersionTypeString() const;
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
QString gitHash() const { return _gitHash; }
quint64 vehicleUID() const { return _uid; }
bool soloFirmware() const { return _soloFirmware; }
int defaultComponentId() { return _defaultComponentId; }
/// Sets the default component id for an offline editing vehicle
void setOfflineEditingDefaultComponentId(int defaultComponentId);
/// @return -1 = Unknown, Number of motors on vehicle
/// @return true: Motors are coaxial like an X8 config, false: Quadcopter for example
/// @return true: X confiuration, false: Plus configuration
/// @return Firmware plugin instance data associated with this Vehicle
QObject* firmwarePluginInstanceData() { return _firmwarePluginInstanceData; }
/// Sets the firmware plugin instance data associated with this Vehicle. This object will be parented to the Vehicle
/// and destroyed when the vehicle goes away.
void setFirmwarePluginInstanceData(QObject* firmwarePluginInstanceData);
QString vehicleImageOpaque () const;
QString vehicleImageOutline () const;
QString vehicleImageCompass () const;
const QVariantList& toolIndicators ();
const QVariantList& modeIndicators ();
const QVariantList& staticCameraList () const;
uint64_t capabilityBits () const { return _capabilityBits; } // Change signalled by capabilityBitsChanged
/// The vehicle is responsible for making the initial request for the Plan.
/// @return: true: initial request is complete, false: initial request is still in progress;
bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; }
void forceInitialPlanRequestComplete();
void _setFlying(bool flying);
void _setLanding(bool landing);
void _setHomePosition(QGeoCoordinate& homeCoord);
void _setMaxProtoVersion(unsigned version);
void _setMaxProtoVersionFromBothSources();
/// Vehicle is about to be deleted
void prepareDelete();
quint64 mavlinkSentCount () { return _mavlinkSentCount; } /// Calculated total number of messages sent to us
quint64 mavlinkReceivedCount () { return _mavlinkReceivedCount; } /// Total number of sucessful messages received
quint64 mavlinkLossCount () { return _mavlinkLossCount; } /// Total number of lost messages
float mavlinkLossPercent () { return _mavlinkLossPercent; } /// Running loss rate
qreal gimbalRoll () { return static_cast<qreal>(_curGimbalRoll);}
qreal gimbalPitch () { return static_cast<qreal>(_curGimbalPitch); }
qreal gimbalYaw () { return static_cast<qreal>(_curGinmbalYaw); }
bool gimbalData () { return _haveGimbalData; }
bool isROIEnabled () { return _isROIEnabled; }
CheckList checkListState () { return _checkListState; }
void setCheckListState (CheckList cl) { _checkListState = cl; emit checkListStateChanged(); }
void _offlineFirmwareTypeSettingChanged (QVariant varFirmwareType); // Should only be used by MissionControler to set firmware from Plan file
void _offlineVehicleTypeSettingChanged (QVariant varVehicleType); // Should only be used by MissionController to set vehicle type from Plan file
void allLinksInactive (Vehicle* vehicle);
void coordinateChanged (QGeoCoordinate coordinate);
void joystickEnabledChanged (bool enabled);
void activeChanged (bool active);
void mavlinkMessageReceived (const mavlink_message_t& message);
void homePositionChanged (const QGeoCoordinate& homePosition);
void armedChanged (bool armed);
void flightModeChanged (const QString& flightMode);
void connectionLostChanged (bool connectionLost);
void connectionLostEnabledChanged (bool connectionLostEnabled);
void autoDisconnectChanged (bool autoDisconnectChanged);
void flyingChanged (bool flying);
void landingChanged (bool landing);
void guidedModeChanged (bool guidedMode);
void vtolInFwdFlightChanged (bool vtolInFwdFlight);
void prearmErrorChanged (const QString& prearmError);
void soloFirmwareChanged (bool soloFirmware);
void defaultCruiseSpeedChanged (double cruiseSpeed);
void defaultHoverSpeedChanged (double hoverSpeed);
void firmwareTypeChanged ();
void vehicleTypeChanged ();
void hobbsMeterChanged ();
void capabilitiesKnownChanged (bool capabilitiesKnown);
void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete);
void capabilityBitsChanged (uint64_t capabilityBits);
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
void highLatencyLinkChanged (bool highLatencyLink);
void priorityLinkNameChanged (const QString& priorityLinkName);
void linksChanged ();
void linksPropertiesChanged ();
void textMessageReceived (int uasid, int componentid, int severity, QString text);
void checkListStateChanged ();
void messagesReceivedChanged ();
void messagesSentChanged ();
void messagesLostChanged ();
void messageTypeChanged ();
void newMessageCountChanged ();
void messageCountChanged ();
void formatedMessagesChanged ();
void formatedMessageChanged ();
void latestErrorChanged ();
void longitudeChanged ();
void currentConfigChanged ();
void flowImageIndexChanged ();
void rcRSSIChanged (int rcRSSI);
void telemetryRRSSIChanged (int value);
void telemetryLRSSIChanged (int value);
void telemetryRXErrorsChanged (unsigned int value);
void telemetryFixedChanged (unsigned int value);
void telemetryTXBufferChanged (unsigned int value);
void telemetryLNoiseChanged (int value);
void telemetryRNoiseChanged (int value);
void autoDisarmChanged ();
void flightModesChanged ();
void sensorsPresentBitsChanged (int sensorsPresentBits);
void sensorsEnabledBitsChanged (int sensorsEnabledBits);
void sensorsHealthBitsChanged (int sensorsHealthBits);
void sensorsUnhealthyBitsChanged (int sensorsUnhealthyBits);
void orbitActiveChanged (bool orbitActive);
void readyToFlyAvailableChanged (bool readyToFlyAvailable);
void readyToFlyChanged (bool readyToFy);
void allSensorsHealthyChanged (bool allSensorsHealthy);
void firmwareVersionChanged ();
void firmwareCustomVersionChanged ();
void gitHashChanged (QString hash);
void vehicleUIDChanged ();
/// @param channelCount Number of available channels, cMaxRcChannels max
/// @param pwmValues -1 signals channel not available
void rcChannelsChanged (int channelCount, int pwmValues[cMaxRcChannels]);
/// Remote control RSSI changed (0% - 100%)
void remoteControlRSSIChanged (uint8_t rssi);
void mavlinkRawImu (mavlink_message_t message);
void mavlinkScaledImu1 (mavlink_message_t message);
void mavlinkScaledImu2 (mavlink_message_t message);
void mavlinkScaledImu3 (mavlink_message_t message);
// Mavlink Log Download
void mavlinkLogData (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked);
/// Signalled in response to usage of sendMavCommand
/// @param vehicleId Vehicle which command was sent to
/// @param component Component which command was sent to
/// @param command MAV_CMD Command which was sent
/// @param result MAV_RESULT returned in ack
/// @param noResponseFromVehicle true: vehicle did not respond to command, false: vehicle responsed, MAV_RESULT in result
void mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
void mavlinkSerialControl (uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
void requestProtocolVersion (unsigned version);
void mavlinkStatusChanged ();
void gimbalRollChanged ();
void gimbalPitchChanged ();
void gimbalYawChanged ();
void gimbalDataChanged ();
void isROIEnabledChanged ();
void _mavlinkMessageReceived (LinkInterface* link, mavlink_message_t message);
void _linkInactiveOrDeleted (LinkInterface* link);
void _sendMessageMultipleNext ();
void _parametersReady (bool parametersReady);
void _remoteControlRSSIChanged (uint8_t rssi);
void _handleFlightModeChanged (const QString& flightMode);
void _announceArmedChanged (bool armed);
void _offlineCruiseSpeedSettingChanged(QVariant value);
void _offlineHoverSpeedSettingChanged(QVariant value);
void _updateHighLatencyLink (bool sendCommand = true);
void _handleTextMessage (int newCount);
void _handletextMessageReceived (UASMessage* message);
void _imageReady (UASInterface* uas);
void _prearmErrorTimeout ();
void _firstMissionLoadComplete ();
void _firstGeoFenceLoadComplete ();
void _firstRallyPointLoadComplete ();
void _sendMavCommandAgain ();
void _clearCameraTriggerPoints ();
void _updateDistanceHeadingToHome ();
void _updateMissionItemIndex ();
void _updateHeadingToNextWP ();
void _updateDistanceToGCS ();
void _updateHobbsMeter ();
void _vehicleParamLoaded (bool ready);
void _sendQGCTimeToVehicle ();
void _mavlinkMessageStatus (int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent);
void _trafficUpdate (bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
void _orbitTelemetryTimeout ();
void _updateFlightTime ();
bool _containsLink (LinkInterface* link);
void _addLink (LinkInterface* link);
void _joystickChanged (Joystick* joystick);
void _loadSettings ();
void _saveSettings ();
void _startJoystick (bool start);
void _handlePing (LinkInterface* link, mavlink_message_t& message);
void _handleHomePosition (mavlink_message_t& message);
void _handleHeartbeat (mavlink_message_t& message);
void _handleRadioStatus (mavlink_message_t& message);
void _handleRCChannels (mavlink_message_t& message);
void _handleBatteryStatus (mavlink_message_t& message);
void _handleSysStatus (mavlink_message_t& message);
void _handleExtendedSysState (mavlink_message_t& message);
void _handleCommandAck (mavlink_message_t& message);
void _handleCommandLong (mavlink_message_t& message);
void _handleGpsRawInt (mavlink_message_t& message);
void _handleGlobalPositionInt (mavlink_message_t& message);
void _handleAltitude (mavlink_message_t& message);
void _handleVfrHud (mavlink_message_t& message);
void _handleHighLatency (mavlink_message_t& message);
void _handleHighLatency2 (mavlink_message_t& message);
void _handleAttitudeWorker (double rollRadians, double pitchRadians, double yawRadians);
void _handleAttitude (mavlink_message_t& message);
void _handleAttitudeQuaternion (mavlink_message_t& message);
void _handleOrbitExecutionStatus (const mavlink_message_t& message);
void _handleMessageInterval (const mavlink_message_t& message);
void _handleGimbalOrientation (const mavlink_message_t& message);
void _handleObstacleDistance (const mavlink_message_t& message);
Gus Grubba
committed
// ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
void _handleCameraFeedback (const mavlink_message_t& message);
Gus Grubba
committed
#endif
void _handleCameraImageCaptured (const mavlink_message_t& message);
void _handleADSBVehicle (const mavlink_message_t& message);
void _missionManagerError (int errorCode, const QString& errorMsg);
void _geoFenceManagerError (int errorCode, const QString& errorMsg);
void _rallyPointManagerError (int errorCode, const QString& errorMsg);
void _linkActiveChanged (LinkInterface* link, bool active, int vehicleID);
void _say (const QString& text);
QString _vehicleIdSpeech ();
void _handleMavlinkLoggingData (mavlink_message_t& message);
void _handleMavlinkLoggingDataAcked (mavlink_message_t& message);
void _ackMavlinkLogData (uint16_t sequence);
void _sendNextQueuedMavCommand ();
void _updatePriorityLink (bool updateActive, bool sendCommand);
void _commonInit ();
void _setupAutoDisarmSignalling ();
void _setCapabilities (uint64_t capabilityBits);
void _updateArmed (bool armed);
bool _apmArmingNotRequired ();
void _pidTuningAdjustRates (bool setRatesForTuning);
void _initializeCsv ();
void _writeCsvLine ();
void _flightTimerStart ();
void _flightTimerStop ();
void _chunkedStatusTextTimeout (void);
void _chunkedStatusTextCompleted (uint8_t compId);
bool _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
QObject* _firmwarePluginInstanceData;
SettingsManager* _settingsManager;
QTimer _csvLogTimer;
QFile _csvLogFile;