Skip to content
Snippets Groups Projects
Vehicle.cc 171 KiB
Newer Older
  • Learn to ignore specific revisions
  • /****************************************************************************
     *
     *   (c) 2009-2016 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.
     *
     ****************************************************************************/
    
    dheideman's avatar
    dheideman committed
    #include <QTime>
    #include <QDateTime>
    #include <QLocale>
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    #include <QQuaternion>
    
    
    #include "Vehicle.h"
    #include "MAVLinkProtocol.h"
    #include "FirmwarePluginManager.h"
    #include "LinkManager.h"
    #include "FirmwarePlugin.h"
    
    #include "JoystickManager.h"
    
    Don Gagne's avatar
    Don Gagne committed
    #include "MissionManager.h"
    
    Don Gagne's avatar
    Don Gagne committed
    #include "MissionController.h"
    
    #include "PlanMasterController.h"
    
    #include "GeoFenceManager.h"
    #include "RallyPointManager.h"
    
    #include "CoordinateVector.h"
    
    #include "ParameterManager.h"
    
    #include "QGCApplication.h"
    
    dogmaphobic's avatar
    dogmaphobic committed
    #include "QGCImageProvider.h"
    
    #include "MissionCommandTree.h"
    
    #include "QGroundControlQmlGlobal.h"
    
    #include "SettingsManager.h"
    
    #include "QGCQGeoCoordinate.h"
    
    #include "QGCCorePlugin.h"
    
    Don Gagne's avatar
     
    Don Gagne committed
    #include "QGCOptions.h"
    
    #include "ADSBVehicle.h"
    
    #include "QGCCameraManager.h"
    
    #include "VideoReceiver.h"
    #include "VideoManager.h"
    
    Don Gagne's avatar
     
    Don Gagne committed
    #include "PositionManager.h"
    
    Gus Grubba's avatar
    Gus Grubba committed
    #include "VehicleObjectAvoidance.h"
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
    #include "TrajectoryPoints.h"
    
    Gus Grubba's avatar
    Gus Grubba committed
    
    
    #if defined(QGC_AIRMAP_ENABLED)
    #include "AirspaceVehicleManager.h"
    #endif
    
    
    QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
    
    
    #define UPDATE_TIMER 50
    #define DEFAULT_LAT  38.965767f
    #define DEFAULT_LON -120.083923f
    
    
    const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle.");
    
    const char* Vehicle::_settingsGroup =               "Vehicle%1";        // %1 replaced with mavlink system id
    const char* Vehicle::_joystickModeSettingsKey =     "JoystickMode";
    const char* Vehicle::_joystickEnabledSettingsKey =  "JoystickEnabled";
    
    Don Gagne's avatar
    Don Gagne committed
    const char* Vehicle::_rollFactName =                "roll";
    const char* Vehicle::_pitchFactName =               "pitch";
    const char* Vehicle::_headingFactName =             "heading";
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    const char* Vehicle::_rollRateFactName =             "rollRate";
    const char* Vehicle::_pitchRateFactName =           "pitchRate";
    const char* Vehicle::_yawRateFactName =             "yawRate";
    
    Don Gagne's avatar
    Don Gagne committed
    const char* Vehicle::_airSpeedFactName =            "airSpeed";
    const char* Vehicle::_groundSpeedFactName =         "groundSpeed";
    const char* Vehicle::_climbRateFactName =           "climbRate";
    const char* Vehicle::_altitudeRelativeFactName =    "altitudeRelative";
    const char* Vehicle::_altitudeAMSLFactName =        "altitudeAMSL";
    
    const char* Vehicle::_flightDistanceFactName =      "flightDistance";
    
    const char* Vehicle::_flightTimeFactName =          "flightTime";
    
    const char* Vehicle::_distanceToHomeFactName =      "distanceToHome";
    
    const char* Vehicle::_headingToNextWPFactName =     "headingToNextWP";
    
    Don Gagne's avatar
     
    Don Gagne committed
    const char* Vehicle::_headingToHomeFactName =       "headingToHome";
    
    Don Gagne's avatar
     
    Don Gagne committed
    const char* Vehicle::_distanceToGCSFactName =       "distanceToGCS";
    
    const char* Vehicle::_hobbsFactName =               "hobbs";
    
    Don Gagne's avatar
     
    Don Gagne committed
    const char* Vehicle::_throttlePctFactName =         "throttlePct";
    
    const char* Vehicle::_gpsFactGroupName =                "gps";
    const char* Vehicle::_battery1FactGroupName =           "battery";
    const char* Vehicle::_battery2FactGroupName =           "battery2";
    const char* Vehicle::_windFactGroupName =               "wind";
    const char* Vehicle::_vibrationFactGroupName =          "vibration";
    const char* Vehicle::_temperatureFactGroupName =        "temperature";
    const char* Vehicle::_clockFactGroupName =              "clock";
    const char* Vehicle::_distanceSensorFactGroupName =     "distanceSensor";
    const char* Vehicle::_estimatorStatusFactGroupName =    "estimatorStatus";
    
    Don Gagne's avatar
     
    Don Gagne committed
    // Standard connected vehicle
    
    Vehicle::Vehicle(LinkInterface*             link,
                     int                        vehicleId,
    
                     int                        defaultComponentId,
    
                     MAV_AUTOPILOT              firmwareType,
                     MAV_TYPE                   vehicleType,
                     FirmwarePluginManager*     firmwarePluginManager,
                     JoystickManager*           joystickManager)
    
    Don Gagne's avatar
    Don Gagne committed
        : FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json")
        , _id(vehicleId)
    
        , _defaultComponentId(defaultComponentId)
    
        , _active(false)
    
        , _offlineEditingVehicle(false)
    
        , _firmwareType(firmwareType)
    
        , _vehicleType(vehicleType)
    
        , _firmwarePlugin(nullptr)
        , _firmwarePluginInstanceData(nullptr)
        , _autopilotPlugin(nullptr)
        , _mavlink(nullptr)
    
        , _soloFirmware(false)
    
        , _toolbox(qgcApp()->toolbox())
        , _settingsManager(_toolbox->settingsManager())
    
        , _csvLogTimer(this)
    
        , _joystickMode(JoystickModeRC)
    
        , _joystickEnabled(false)
    
        , _uas(nullptr)
        , _mav(nullptr)
    
        , _currentMessageCount(0)
        , _messageCount(0)
        , _currentErrorCount(0)
        , _currentWarningCount(0)
        , _currentNormalCount(0)
        , _currentMessageType(MessageNone)
        , _updateCount(0)
    
        , _rcRSSI(255)
    
        , _rcRSSIstore(255.)
    
    Don Gagne's avatar
    Don Gagne committed
        , _autoDisconnect(false)
    
    Don Gagne's avatar
    Don Gagne committed
        , _flying(false)
    
        , _vtolInFwdFlight(false)
    
        , _onboardControlSensorsPresent(0)
        , _onboardControlSensorsEnabled(0)
        , _onboardControlSensorsHealth(0)
        , _onboardControlSensorsUnhealthy(0)
    
        , _gpsRawIntMessageAvailable(false)
        , _globalPositionIntMessageAvailable(false)
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        , _defaultCruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
        , _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
    
    Gus Grubba's avatar
    Gus Grubba committed
        , _telemetryRRSSI(0)
        , _telemetryLRSSI(0)
        , _telemetryRXErrors(0)
        , _telemetryFixed(0)
        , _telemetryTXBuffer(0)
        , _telemetryLNoise(0)
        , _telemetryRNoise(0)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _mavlinkProtocolRequestComplete(false)
    
        , _vehicleCapabilitiesKnown(false)
    
        , _capabilityBits(0)
    
        , _highLatencyLink(false)
    
        , _receivingAttitudeQuaternion(false)
    
        , _cameras(nullptr)
    
        , _connectionLost(false)
        , _connectionLostEnabled(true)
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        , _initialPlanRequestComplete(false)
    
        , _missionManager(nullptr)
    
        , _missionManagerInitialRequestSent(false)
    
        , _geoFenceManager(nullptr)
    
        , _geoFenceManagerInitialRequestSent(false)
    
        , _rallyPointManager(nullptr)
    
        , _rallyPointManagerInitialRequestSent(false)
    
    #if defined(QGC_AIRMAP_ENABLED)
    
    Don Gagne's avatar
    Don Gagne committed
        , _armed(false)
        , _base_mode(0)
        , _custom_mode(0)
    
        , _nextSendMessageMultipleIndex(0)
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
        , _trajectoryPoints(new TrajectoryPoints(this, this))
    
        , _firmwarePluginManager(firmwarePluginManager)
        , _joystickManager(joystickManager)
    
    dogmaphobic's avatar
    dogmaphobic committed
        , _flowImageIndex(0)
    
    Don Gagne's avatar
    Don Gagne committed
        , _allLinksInactiveSent(false)
    
        , _messagesReceived(0)
        , _messagesSent(0)
        , _messagesLost(0)
        , _messageSeq(0)
        , _compID(0)
        , _heardFrom(false)
    
        , _firmwareMajorVersion(versionNotSetValue)
        , _firmwareMinorVersion(versionNotSetValue)
        , _firmwarePatchVersion(versionNotSetValue)
    
        , _firmwareCustomMajorVersion(versionNotSetValue)
        , _firmwareCustomMinorVersion(versionNotSetValue)
        , _firmwareCustomPatchVersion(versionNotSetValue)
    
        , _firmwareVersionType(FIRMWARE_VERSION_TYPE_OFFICIAL)
    
        , _gitHash(versionNotSetValue)
    
    Gus Grubba's avatar
    Gus Grubba committed
        , _uid(0)
    
        , _lastAnnouncedLowBatteryPercent(100)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _orbitActive(false)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _pidTuningTelemetryMode(false)
        , _pidTuningWaitingForRates(false)
    
    Don Gagne's avatar
    Don Gagne committed
        , _rollFact             (0, _rollFactName,              FactMetaData::valueTypeDouble)
        , _pitchFact            (0, _pitchFactName,             FactMetaData::valueTypeDouble)
        , _headingFact          (0, _headingFactName,           FactMetaData::valueTypeDouble)
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        , _rollRateFact         (0, _rollRateFactName,          FactMetaData::valueTypeDouble)
        , _pitchRateFact        (0, _pitchRateFactName,         FactMetaData::valueTypeDouble)
        , _yawRateFact          (0, _yawRateFactName,           FactMetaData::valueTypeDouble)
    
    Don Gagne's avatar
    Don Gagne committed
        , _groundSpeedFact      (0, _groundSpeedFactName,       FactMetaData::valueTypeDouble)
        , _airSpeedFact         (0, _airSpeedFactName,          FactMetaData::valueTypeDouble)
        , _climbRateFact        (0, _climbRateFactName,         FactMetaData::valueTypeDouble)
        , _altitudeRelativeFact (0, _altitudeRelativeFactName,  FactMetaData::valueTypeDouble)
        , _altitudeAMSLFact     (0, _altitudeAMSLFactName,      FactMetaData::valueTypeDouble)
    
        , _flightDistanceFact   (0, _flightDistanceFactName,    FactMetaData::valueTypeDouble)
    
        , _flightTimeFact       (0, _flightTimeFactName,        FactMetaData::valueTypeElapsedTimeInSeconds)
    
        , _distanceToHomeFact   (0, _distanceToHomeFactName,    FactMetaData::valueTypeDouble)
    
        , _headingToNextWPFact  (0, _headingToNextWPFactName,   FactMetaData::valueTypeDouble)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _headingToHomeFact    (0, _headingToHomeFactName,     FactMetaData::valueTypeDouble)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _distanceToGCSFact    (0, _distanceToGCSFactName,     FactMetaData::valueTypeDouble)
    
        , _hobbsFact            (0, _hobbsFactName,             FactMetaData::valueTypeString)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _throttlePctFact      (0, _throttlePctFactName,       FactMetaData::valueTypeUint16)
    
    Don Gagne's avatar
    Don Gagne committed
        , _gpsFactGroup(this)
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        , _battery1FactGroup(this)
        , _battery2FactGroup(this)
    
    Don Gagne's avatar
    Don Gagne committed
        , _windFactGroup(this)
    
        , _vibrationFactGroup(this)
    
        , _temperatureFactGroup(this)
    
    dheideman's avatar
    dheideman committed
        , _clockFactGroup(this)
    
        , _distanceSensorFactGroup(this)
    
        , _estimatorStatusFactGroup(this)
    
        connect(_joystickManager, &JoystickManager::activeJoystickChanged, this, &Vehicle::_loadSettings);
        connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleAvailableChanged, this, &Vehicle::_loadSettings);
    
        _mavlink = _toolbox->mavlinkProtocol();
    
    Don Gagne's avatar
     
    Don Gagne committed
        qCDebug(VehicleLog) << "Link started with Mavlink " << (_mavlink->getCurrentVersion() >= 200 ? "V2" : "V1");
    
        connect(_mavlink, &MAVLinkProtocol::messageReceived,        this, &Vehicle::_mavlinkMessageReceived);
        connect(_mavlink, &MAVLinkProtocol::mavlinkMessageStatus,   this, &Vehicle::_mavlinkMessageStatus);
    
        connect(this, &Vehicle::_sendMessageOnLinkOnThread, this, &Vehicle::_sendMessageOnLink, Qt::QueuedConnection);
    
    Don Gagne's avatar
    Don Gagne committed
        connect(this, &Vehicle::flightModeChanged,          this, &Vehicle::_handleFlightModeChanged);
    
        connect(this, &Vehicle::armedChanged,               this, &Vehicle::_announceArmedChanged);
    
        connect(_toolbox->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &Vehicle::_vehicleParamLoaded);
    
    
        _uas = new UAS(_mavlink, this, _firmwarePluginManager);
    
    Don Gagne's avatar
    Don Gagne committed
        connect(_uas, &UAS::imageReady,                     this, &Vehicle::_imageReady);
        connect(this, &Vehicle::remoteControlRSSIChanged,   this, &Vehicle::_remoteControlRSSIChanged);
    
    Don Gagne's avatar
    Don Gagne committed
        _autopilotPlugin = _firmwarePlugin->autopilotPlugin(this);
    
    Don Gagne's avatar
    Don Gagne committed
        // PreArm Error self-destruct timer
        connect(&_prearmErrorTimer, &QTimer::timeout, this, &Vehicle::_prearmErrorTimeout);
        _prearmErrorTimer.setInterval(_prearmErrorTimeoutMSecs);
        _prearmErrorTimer.setSingleShot(true);
    
    
        // Send MAV_CMD ack timer
        _mavCommandAckTimer.setSingleShot(true);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        _mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
    
        connect(&_mavCommandAckTimer, &QTimer::timeout, this, &Vehicle::_sendMavCommandAgain);
    
    
        // Listen for system messages
    
        connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged,  this, &Vehicle::_handleTextMessage);
        connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageReceived,      this, &Vehicle::_handletextMessageReceived);
    
        if (_highLatencyLink || link->isPX4Flow()) {
            // These links don't request information
    
            _setMaxProtoVersion(100);
            _setCapabilities(0);
            _initialPlanRequestComplete = true;
            _missionManagerInitialRequestSent = true;
            _geoFenceManagerInitialRequestSent = true;
            _rallyPointManagerInitialRequestSent = true;
        } else {
    
    Don Gagne's avatar
     
    Don Gagne committed
            sendMavCommand(MAV_COMP_ID_ALL,
    
                           MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
                           false,                                   // No error shown if fails
                           1);                                      // Request firmware version
    
    Don Gagne's avatar
     
    Don Gagne committed
            sendMavCommand(MAV_COMP_ID_ALL,
                           MAV_CMD_REQUEST_PROTOCOL_VERSION,
                           false,                                   // No error shown if fails
                           1);                                      // Request protocol version
    
        _firmwarePlugin->initializeVehicle(this);
    
        for(auto& factName: factNames()) {
            _firmwarePlugin->adjustMetaData(vehicleType, getFact(factName)->metaData());
        }
    
        _sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay);
        connect(&_sendMultipleTimer, &QTimer::timeout, this, &Vehicle::_sendMessageMultipleNext);
    
    Don Gagne's avatar
     
    Don Gagne committed
        connect(&_orbitTelemetryTimer, &QTimer::timeout, this, &Vehicle::_orbitTelemetryTimeout);
    
    
        // Create camera manager instance
    
        _cameras = _firmwarePlugin->createCameraManager(this);
    
        emit dynamicCamerasChanged();
    
        connect(&_adsbTimer, &QTimer::timeout, this, &Vehicle::_adsbTimerTimeout);
        _adsbTimer.setSingleShot(false);
        _adsbTimer.start(1000);
    
    
        // Start csv logger
        connect(&_csvLogTimer, &QTimer::timeout, this, &Vehicle::_writeCsvLine);
        _csvLogTimer.start(1000);
    
    // Disconnected Vehicle for offline editing
    Vehicle::Vehicle(MAV_AUTOPILOT              firmwareType,
                     MAV_TYPE                   vehicleType,
                     FirmwarePluginManager*     firmwarePluginManager,
                     QObject*                   parent)
    
        : FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json", parent)
        , _id(0)
    
        , _defaultComponentId(MAV_COMP_ID_ALL)
    
        , _active(false)
    
        , _offlineEditingVehicle(true)
    
        , _firmwareType(firmwareType)
        , _vehicleType(vehicleType)
    
        , _firmwarePlugin(nullptr)
        , _firmwarePluginInstanceData(nullptr)
        , _autopilotPlugin(nullptr)
        , _mavlink(nullptr)
    
        , _soloFirmware(false)
    
        , _toolbox(qgcApp()->toolbox())
        , _settingsManager(_toolbox->settingsManager())
    
        , _csvLogTimer(this)
    
        , _joystickMode(JoystickModeRC)
        , _joystickEnabled(false)
    
        , _uas(nullptr)
        , _mav(nullptr)
    
        , _currentMessageCount(0)
        , _messageCount(0)
        , _currentErrorCount(0)
        , _currentWarningCount(0)
        , _currentNormalCount(0)
        , _currentMessageType(MessageNone)
        , _updateCount(0)
    
        , _rcRSSI(255)
    
        , _rcRSSIstore(255.)
    
        , _autoDisconnect(false)
    
        , _vtolInFwdFlight(false)
    
        , _onboardControlSensorsPresent(0)
        , _onboardControlSensorsEnabled(0)
        , _onboardControlSensorsHealth(0)
        , _onboardControlSensorsUnhealthy(0)
    
        , _gpsRawIntMessageAvailable(false)
        , _globalPositionIntMessageAvailable(false)
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        , _defaultCruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
        , _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _mavlinkProtocolRequestComplete(true)
        , _maxProtoVersion(200)
    
        , _vehicleCapabilitiesKnown(true)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _capabilityBits(MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY)
    
        , _highLatencyLink(false)
    
        , _receivingAttitudeQuaternion(false)
    
        , _cameras(nullptr)
    
        , _connectionLost(false)
        , _connectionLostEnabled(true)
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        , _initialPlanRequestComplete(false)
    
        , _missionManager(nullptr)
    
        , _missionManagerInitialRequestSent(false)
    
        , _geoFenceManager(nullptr)
    
        , _geoFenceManagerInitialRequestSent(false)
    
        , _rallyPointManager(nullptr)
    
        , _rallyPointManagerInitialRequestSent(false)
    
    #if defined(QGC_AIRMAP_ENABLED)
    
        , _armed(false)
        , _base_mode(0)
        , _custom_mode(0)
        , _nextSendMessageMultipleIndex(0)
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
        , _trajectoryPoints(new TrajectoryPoints(this, this))
    
        , _firmwarePluginManager(firmwarePluginManager)
    
        , _joystickManager(nullptr)
    
        , _flowImageIndex(0)
        , _allLinksInactiveSent(false)
        , _messagesReceived(0)
        , _messagesSent(0)
        , _messagesLost(0)
        , _messageSeq(0)
        , _compID(0)
        , _heardFrom(false)
    
        , _firmwareMajorVersion(versionNotSetValue)
        , _firmwareMinorVersion(versionNotSetValue)
        , _firmwarePatchVersion(versionNotSetValue)
    
        , _firmwareCustomMajorVersion(versionNotSetValue)
        , _firmwareCustomMinorVersion(versionNotSetValue)
        , _firmwareCustomPatchVersion(versionNotSetValue)
        , _firmwareVersionType(FIRMWARE_VERSION_TYPE_OFFICIAL)
    
        , _gitHash(versionNotSetValue)
    
    Gus Grubba's avatar
    Gus Grubba committed
        , _uid(0)
    
        , _lastAnnouncedLowBatteryPercent(100)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _orbitActive(false)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _pidTuningTelemetryMode(false)
        , _pidTuningWaitingForRates(false)
    
        , _rollFact             (0, _rollFactName,              FactMetaData::valueTypeDouble)
        , _pitchFact            (0, _pitchFactName,             FactMetaData::valueTypeDouble)
        , _headingFact          (0, _headingFactName,           FactMetaData::valueTypeDouble)
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        , _rollRateFact         (0, _rollRateFactName,          FactMetaData::valueTypeDouble)
        , _pitchRateFact        (0, _pitchRateFactName,         FactMetaData::valueTypeDouble)
        , _yawRateFact          (0, _yawRateFactName,           FactMetaData::valueTypeDouble)
    
        , _groundSpeedFact      (0, _groundSpeedFactName,       FactMetaData::valueTypeDouble)
        , _airSpeedFact         (0, _airSpeedFactName,          FactMetaData::valueTypeDouble)
        , _climbRateFact        (0, _climbRateFactName,         FactMetaData::valueTypeDouble)
        , _altitudeRelativeFact (0, _altitudeRelativeFactName,  FactMetaData::valueTypeDouble)
        , _altitudeAMSLFact     (0, _altitudeAMSLFactName,      FactMetaData::valueTypeDouble)
    
        , _flightDistanceFact   (0, _flightDistanceFactName,    FactMetaData::valueTypeDouble)
        , _flightTimeFact       (0, _flightTimeFactName,        FactMetaData::valueTypeElapsedTimeInSeconds)
    
        , _distanceToHomeFact   (0, _distanceToHomeFactName,    FactMetaData::valueTypeDouble)
    
        , _headingToNextWPFact  (0, _headingToNextWPFactName,   FactMetaData::valueTypeDouble)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _headingToHomeFact    (0, _headingToHomeFactName,     FactMetaData::valueTypeDouble)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _distanceToGCSFact    (0, _distanceToGCSFactName,     FactMetaData::valueTypeDouble)
    
        , _hobbsFact            (0, _hobbsFactName,             FactMetaData::valueTypeString)
    
    Don Gagne's avatar
     
    Don Gagne committed
        , _throttlePctFact      (0, _throttlePctFactName,       FactMetaData::valueTypeUint16)
    
        , _gpsFactGroup(this)
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        , _battery1FactGroup(this)
        , _battery2FactGroup(this)
    
        , _windFactGroup(this)
        , _vibrationFactGroup(this)
    
    dheideman's avatar
    dheideman committed
        , _clockFactGroup(this)
    
        , _distanceSensorFactGroup(this)
    
    Don Gagne's avatar
     
    Don Gagne committed
    
        // Offline editing vehicle tracks settings changes for offline editing settings
        connect(_settingsManager->appSettings()->offlineEditingFirmwareType(),  &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
        connect(_settingsManager->appSettings()->offlineEditingVehicleType(),   &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
        connect(_settingsManager->appSettings()->offlineEditingCruiseSpeed(),   &Fact::rawValueChanged, this, &Vehicle::_offlineCruiseSpeedSettingChanged);
        connect(_settingsManager->appSettings()->offlineEditingHoverSpeed(),    &Fact::rawValueChanged, this, &Vehicle::_offlineHoverSpeedSettingChanged);
    
    
        _firmwarePlugin->initializeVehicle(this);
    
    }
    
    void Vehicle::_commonInit(void)
    {
        _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
    
        connect(_firmwarePlugin, &FirmwarePlugin::toolbarIndicatorsChanged, this, &Vehicle::toolBarIndicatorsChanged);
    
    
    Don Gagne's avatar
     
    Don Gagne committed
        connect(this, &Vehicle::coordinateChanged,      this, &Vehicle::_updateDistanceHeadingToHome);
    
    Don Gagne's avatar
     
    Don Gagne committed
        connect(this, &Vehicle::coordinateChanged,      this, &Vehicle::_updateDistanceToGCS);
    
    Don Gagne's avatar
     
    Don Gagne committed
        connect(this, &Vehicle::homePositionChanged,    this, &Vehicle::_updateDistanceHeadingToHome);
    
        connect(this, &Vehicle::hobbsMeterChanged,      this, &Vehicle::_updateHobbsMeter);
    
    Don Gagne's avatar
     
    Don Gagne committed
        connect(_toolbox->qgcPositionManager(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateDistanceToGCS);
    
    
        _missionManager = new MissionManager(this);
    
        connect(_missionManager, &MissionManager::error,                    this, &Vehicle::_missionManagerError);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_missionLoadComplete);
    
        connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearCameraTriggerPoints);
        connect(_missionManager, &MissionManager::sendComplete,             this, &Vehicle::_clearCameraTriggerPoints);
    
        connect(_missionManager, &MissionManager::currentIndexChanged,      this, &Vehicle::_updateHeadingToNextWP);
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
        connect(_missionManager, &MissionManager::sendComplete,             _trajectoryPoints, &TrajectoryPoints::clear);
        connect(_missionManager, &MissionManager::newMissionItemsAvailable, _trajectoryPoints, &TrajectoryPoints::clear);
    
    
        _parameterManager = new ParameterManager(this);
    
    Don Gagne's avatar
    Don Gagne committed
        connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
    
    Gus Grubba's avatar
    Gus Grubba committed
        _objectAvoidance = new VehicleObjectAvoidance(this, this);
    
    
        // GeoFenceManager needs to access ParameterManager so make sure to create after
    
        _geoFenceManager = new GeoFenceManager(this);
    
        connect(_geoFenceManager, &GeoFenceManager::error,          this, &Vehicle::_geoFenceManagerError);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        connect(_geoFenceManager, &GeoFenceManager::loadComplete,   this, &Vehicle::_geoFenceLoadComplete);
    
        _rallyPointManager = new RallyPointManager(this);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        connect(_rallyPointManager, &RallyPointManager::error,          this, &Vehicle::_rallyPointManagerError);
        connect(_rallyPointManager, &RallyPointManager::loadComplete,   this, &Vehicle::_rallyPointLoadComplete);
    
        // Flight modes can differ based on advanced mode
        connect(_toolbox->corePlugin(), &QGCCorePlugin::showAdvancedUIChanged, this, &Vehicle::flightModesChanged);
    
    
        // Build FactGroup object model
    
        _addFact(&_rollFact,                _rollFactName);
        _addFact(&_pitchFact,               _pitchFactName);
        _addFact(&_headingFact,             _headingFactName);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        _addFact(&_rollRateFact,            _rollRateFactName);
        _addFact(&_pitchRateFact,           _pitchRateFactName);
        _addFact(&_yawRateFact,             _yawRateFactName);
    
        _addFact(&_groundSpeedFact,         _groundSpeedFactName);
        _addFact(&_airSpeedFact,            _airSpeedFactName);
        _addFact(&_climbRateFact,           _climbRateFactName);
        _addFact(&_altitudeRelativeFact,    _altitudeRelativeFactName);
        _addFact(&_altitudeAMSLFact,        _altitudeAMSLFactName);
    
        _addFact(&_flightDistanceFact,      _flightDistanceFactName);
    
        _addFact(&_flightTimeFact,          _flightTimeFactName);
    
        _addFact(&_distanceToHomeFact,      _distanceToHomeFactName);
    
        _addFact(&_headingToNextWPFact,     _headingToNextWPFactName);
    
    Don Gagne's avatar
     
    Don Gagne committed
        _addFact(&_headingToHomeFact,       _headingToHomeFactName);
    
    Don Gagne's avatar
     
    Don Gagne committed
        _addFact(&_distanceToGCSFact,       _distanceToGCSFactName);
    
    Don Gagne's avatar
     
    Don Gagne committed
        _addFact(&_throttlePctFact,         _throttlePctFactName);
    
    
        _hobbsFact.setRawValue(QVariant(QString("0000:00:00")));
    
        _addFact(&_hobbsFact,               _hobbsFactName);
    
        _addFactGroup(&_gpsFactGroup,               _gpsFactGroupName);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        _addFactGroup(&_battery1FactGroup,          _battery1FactGroupName);
        _addFactGroup(&_battery2FactGroup,          _battery2FactGroupName);
    
        _addFactGroup(&_windFactGroup,              _windFactGroupName);
        _addFactGroup(&_vibrationFactGroup,         _vibrationFactGroupName);
        _addFactGroup(&_temperatureFactGroup,       _temperatureFactGroupName);
        _addFactGroup(&_clockFactGroup,             _clockFactGroupName);
        _addFactGroup(&_distanceSensorFactGroup,    _distanceSensorFactGroupName);
    
        _addFactGroup(&_estimatorStatusFactGroup,   _estimatorStatusFactGroupName);
    
    Jacob Walser's avatar
    Jacob Walser committed
        // Add firmware-specific fact groups, if provided
    
        QMap<QString, FactGroup*>* fwFactGroups = _firmwarePlugin->factGroups();
        if (fwFactGroups) {
            QMapIterator<QString, FactGroup*> i(*fwFactGroups);
            while(i.hasNext()) {
                i.next();
                _addFactGroup(i.value(), i.key());
            }
    
        _flightDistanceFact.setRawValue(0);
    
        _flightTimeFact.setRawValue(0);
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
        _flightTimeUpdater.setInterval(1000);
        _flightTimeUpdater.setSingleShot(false);
        connect(&_flightTimeUpdater, &QTimer::timeout, this, &Vehicle::_updateFlightTime);
    
        // Set video stream to udp if running ArduSub and Video is disabled
    
        if (sub() && _settingsManager->videoSettings()->videoSource()->rawValue() == VideoSettings::videoDisabled) {
    
    Gus Grubba's avatar
    Gus Grubba committed
            _settingsManager->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264);
    
        //-- Airspace Management
    #if defined(QGC_AIRMAP_ENABLED)
        AirspaceManager* airspaceManager = _toolbox->airspaceManager();
        if (airspaceManager) {
            _airspaceVehicleManager = airspaceManager->instantiateVehicle(*this);
            if (_airspaceVehicleManager) {
                connect(_airspaceVehicleManager, &AirspaceVehicleManager::trafficUpdate, this, &Vehicle::_trafficUpdate);
            }
        }
    #endif
    
    Don Gagne's avatar
     
    Don Gagne committed
    
        _pidTuningMessages << MAVLINK_MSG_ID_ATTITUDE << MAVLINK_MSG_ID_ATTITUDE_TARGET;
    
    Vehicle::~Vehicle()
    {
    
    Don Gagne's avatar
    Don Gagne committed
        qCDebug(VehicleLog) << "~Vehicle" << this;
    
    
        delete _missionManager;
    
        _missionManager = nullptr;
    
        delete _autopilotPlugin;
    
        _autopilotPlugin = nullptr;
    
        delete _mav;
    
        _mav = nullptr;
    
    #if defined(QGC_AIRMAP_ENABLED)
    
        if (_airspaceVehicleManager) {
            delete _airspaceVehicleManager;
    
    void Vehicle::prepareDelete()
    {
        if(_cameras) {
    
            // because of _cameras QML bindings check for nullptr won't work in the binding pipeline
            // the dangling pointer access will cause a runtime fault
            auto tmpCameras = _cameras;
    
            _cameras = nullptr;
    
            delete tmpCameras;
    
            emit dynamicCamerasChanged();
            qApp->processEvents();
        }
    }
    
    
    void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value)
    {
        _firmwareType = static_cast<MAV_AUTOPILOT>(value.toInt());
    
        _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
    
        emit firmwareTypeChanged();
    }
    
    void Vehicle::_offlineVehicleTypeSettingChanged(QVariant value)
    {
        _vehicleType = static_cast<MAV_TYPE>(value.toInt());
        emit vehicleTypeChanged();
    }
    
    void Vehicle::_offlineCruiseSpeedSettingChanged(QVariant value)
    {
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        _defaultCruiseSpeed = value.toDouble();
        emit defaultCruiseSpeedChanged(_defaultCruiseSpeed);
    
    }
    
    void Vehicle::_offlineHoverSpeedSettingChanged(QVariant value)
    {
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        _defaultHoverSpeed = value.toDouble();
        emit defaultHoverSpeedChanged(_defaultHoverSpeed);
    
    }
    
    QString Vehicle::firmwareTypeString(void) const
    {
        if (px4Firmware()) {
            return QStringLiteral("PX4 Pro");
        } else if (apmFirmware()) {
            return QStringLiteral("ArduPilot");
        } else {
            return tr("MAVLink Generic");
        }
    }
    
    QString Vehicle::vehicleTypeString(void) const
    {
        if (fixedWing()) {
            return tr("Fixed Wing");
        } else if (multiRotor()) {
            return tr("Multi-Rotor");
        } else if (vtol()) {
            return tr("VTOL");
        } else if (rover()) {
            return tr("Rover");
        } else if (sub()) {
            return tr("Sub");
        } else {
            return tr("Unknown");
        }
    }
    
    void Vehicle::resetCounters()
    
    {
        _messagesReceived   = 0;
        _messagesSent       = 0;
        _messagesLost       = 0;
        _messageSeq         = 0;
        _heardFrom          = false;
    }
    
    
    void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message)
    {
    
    Don Gagne's avatar
     
    Don Gagne committed
        // If the link is already running at Mavlink V2 set our max proto version to it.
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        unsigned mavlinkVersion = _mavlink->getCurrentVersion();
        if (_maxProtoVersion != mavlinkVersion && mavlinkVersion >= 200) {
    
    Don Gagne's avatar
     
    Don Gagne committed
            _maxProtoVersion = mavlinkVersion;
            qCDebug(VehicleLog) << "Vehicle::_mavlinkMessageReceived Link already running Mavlink v2. Setting _maxProtoVersion" << _maxProtoVersion;
    
    Don Gagne's avatar
    Don Gagne committed
        if (message.sysid != _id && message.sysid != 0) {
    
            // We allow RADIO_STATUS messages which come from a link the vehicle is using to pass through and be handled
            if (!(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS && _containsLink(link))) {
                return;
            }
    
        if (!_containsLink(link)) {
            _addLink(link);
        }
    
        //-- Check link status
        _messagesReceived++;
        emit messagesReceivedChanged();
        if(!_heardFrom) {
            if(message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
                _heardFrom = true;
                _compID = message.compid;
                _messageSeq = message.seq + 1;
            }
        } else {
            if(_compID == message.compid) {
    
    Gus Grubba's avatar
    Gus Grubba committed
                uint16_t seq_received = static_cast<uint16_t>(message.seq);
    
                uint16_t packet_lost_count = 0;
                //-- Account for overflow during packet loss
                if(seq_received < _messageSeq) {
                    packet_lost_count = (seq_received + 255) - _messageSeq;
                } else {
                    packet_lost_count = seq_received - _messageSeq;
                }
                _messageSeq = message.seq + 1;
                _messagesLost += packet_lost_count;
                if(packet_lost_count)
                    emit messagesLostChanged();
            }
        }
    
    
    Don Gagne's avatar
    Don Gagne committed
        // Give the plugin a change to adjust the message contents
    
        if (!_firmwarePlugin->adjustIncomingMavlinkMessage(this, &message)) {
            return;
        }
    
        // Give the Core Plugin access to all mavlink traffic
        if (!_toolbox->corePlugin()->mavlinkMessage(this, link, message)) {
            return;
        }
    
    
    Don Gagne's avatar
    Don Gagne committed
        switch (message.msgid) {
    
    Don Gagne's avatar
    Don Gagne committed
        case MAVLINK_MSG_ID_HOME_POSITION:
            _handleHomePosition(message);
            break;
        case MAVLINK_MSG_ID_HEARTBEAT:
            _handleHeartbeat(message);
            break;
    
        case MAVLINK_MSG_ID_RADIO_STATUS:
            _handleRadioStatus(message);
            break;
    
    Don Gagne's avatar
    Don Gagne committed
        case MAVLINK_MSG_ID_RC_CHANNELS:
            _handleRCChannels(message);
            break;
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            _handleRCChannelsRaw(message);
            break;
    
    Don Gagne's avatar
    Don Gagne committed
        case MAVLINK_MSG_ID_BATTERY_STATUS:
            _handleBatteryStatus(message);
            break;
        case MAVLINK_MSG_ID_SYS_STATUS:
            _handleSysStatus(message);
            break;
    
        case MAVLINK_MSG_ID_RAW_IMU:
            emit mavlinkRawImu(message);
            break;
        case MAVLINK_MSG_ID_SCALED_IMU:
            emit mavlinkScaledImu1(message);
            break;
        case MAVLINK_MSG_ID_SCALED_IMU2:
            emit mavlinkScaledImu2(message);
            break;
        case MAVLINK_MSG_ID_SCALED_IMU3:
            emit mavlinkScaledImu3(message);
            break;
    
        case MAVLINK_MSG_ID_VIBRATION:
            _handleVibration(message);
            break;
    
    Don Gagne's avatar
    Don Gagne committed
        case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
            _handleExtendedSysState(message);
            break;
    
        case MAVLINK_MSG_ID_COMMAND_ACK:
            _handleCommandAck(message);
            break;
    
        case MAVLINK_MSG_ID_COMMAND_LONG:
            _handleCommandLong(message);
            break;
    
        case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
    
    Gus Grubba's avatar
    Gus Grubba committed
            _handleAutopilotVersion(link, message);
    
        case MAVLINK_MSG_ID_PROTOCOL_VERSION:
            _handleProtocolVersion(link, message);
            break;
    
        case MAVLINK_MSG_ID_WIND_COV:
            _handleWindCov(message);
            break;
    
        case MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS:
            _handleHilActuatorControls(message);
            break;
    
        case MAVLINK_MSG_ID_LOGGING_DATA:
            _handleMavlinkLoggingData(message);
            break;
        case MAVLINK_MSG_ID_LOGGING_DATA_ACKED:
            _handleMavlinkLoggingDataAcked(message);
            break;
    
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            _handleGpsRawInt(message);
            break;
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
            _handleGlobalPositionInt(message);
            break;
        case MAVLINK_MSG_ID_ALTITUDE:
            _handleAltitude(message);
            break;
        case MAVLINK_MSG_ID_VFR_HUD:
            _handleVfrHud(message);
            break;
    
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
            _handleScaledPressure(message);
            break;
        case MAVLINK_MSG_ID_SCALED_PRESSURE2:
            _handleScaledPressure2(message);
            break;
        case MAVLINK_MSG_ID_SCALED_PRESSURE3:
            _handleScaledPressure3(message);
    
            break;
    
        case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
            _handleCameraImageCaptured(message);
    
        case MAVLINK_MSG_ID_ADSB_VEHICLE:
            _handleADSBVehicle(message);
            break;
    
        case MAVLINK_MSG_ID_HIGH_LATENCY2:
            _handleHighLatency2(message);
            break;
    
        case MAVLINK_MSG_ID_ATTITUDE:
            _handleAttitude(message);
            break;
    
        case MAVLINK_MSG_ID_ATTITUDE_QUATERNION:
            _handleAttitudeQuaternion(message);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
            break;
        case MAVLINK_MSG_ID_ATTITUDE_TARGET:
            _handleAttitudeTarget(message);
            break;
    
        case MAVLINK_MSG_ID_DISTANCE_SENSOR:
            _handleDistanceSensor(message);
            break;
    
        case MAVLINK_MSG_ID_ESTIMATOR_STATUS:
            _handleEstimatorStatus(message);
            break;
    
    Don Gagne's avatar
     
    Don Gagne committed
        case MAVLINK_MSG_ID_STATUSTEXT:
    
    Don Gagne's avatar
     
    Don Gagne committed
            _handleStatusText(message, false /* longVersion */);
            break;
        case MAVLINK_MSG_ID_STATUSTEXT_LONG:
            _handleStatusText(message, true /* longVersion */);
    
    Don Gagne's avatar
     
    Don Gagne committed
            break;
    
    Don Gagne's avatar
     
    Don Gagne committed
        case MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS:
            _handleOrbitExecutionStatus(message);
            break;
    
    Don Gagne's avatar
     
    Don Gagne committed
        case MAVLINK_MSG_ID_MESSAGE_INTERVAL:
            _handleMessageInterval(message);
            break;
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        case MAVLINK_MSG_ID_PING:
            _handlePing(link, message);
            break;
    
    Gus Grubba's avatar
    Gus Grubba committed
        case MAVLINK_MSG_ID_MOUNT_ORIENTATION:
            _handleGimbalOrientation(message);
            break;
    
    Gus Grubba's avatar
    Gus Grubba committed
        case MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
            _handleObstacleDistance(message);
            break;
    
        case MAVLINK_MSG_ID_SERIAL_CONTROL:
        {
            mavlink_serial_control_t ser;
            mavlink_msg_serial_control_decode(&message, &ser);
            emit mavlinkSerialControl(ser.device, ser.flags, ser.timeout, ser.baudrate, QByteArray(reinterpret_cast<const char*>(ser.data), ser.count));
        }
            break;
    
            // Following are ArduPilot dialect messages
    
    #if !defined(NO_ARDUPILOT_DIALECT)
        case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
            _handleCameraFeedback(message);
            break;
    
    Don Gagne's avatar
    Don Gagne committed
        case MAVLINK_MSG_ID_WIND:
            _handleWind(message);
            break;
    
        // This must be emitted after the vehicle processes the message. This way the vehicle state is up to date when anyone else
        // does processing.
    
    Don Gagne's avatar
    Don Gagne committed
        emit mavlinkMessageReceived(message);
    
        _uas->receiveMessage(message);
    }
    
    
    void Vehicle::_handleCameraFeedback(const mavlink_message_t& message)
    {
        mavlink_camera_feedback_t feedback;
    
        mavlink_msg_camera_feedback_decode(&message, &feedback);
    
        QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lng / qPow(10.0, 7.0), feedback.alt_msl);
        qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx;
        _cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
    }
    
    Don Gagne's avatar
     
    Don Gagne committed
    void Vehicle::_handleOrbitExecutionStatus(const mavlink_message_t& message)
    {
        mavlink_orbit_execution_status_t orbitStatus;
    
        mavlink_msg_orbit_execution_status_decode(&message, &orbitStatus);
    
        double newRadius =  qAbs(static_cast<double>(orbitStatus.radius));
        if (!qFuzzyCompare(_orbitMapCircle.radius()->rawValue().toDouble(), newRadius)) {
            _orbitMapCircle.radius()->setRawValue(newRadius);
        }
    
        bool newOrbitClockwise = orbitStatus.radius > 0 ? true : false;
        if (_orbitMapCircle.clockwiseRotation() != newOrbitClockwise) {
            _orbitMapCircle.setClockwiseRotation(newOrbitClockwise);
        }
    
        QGeoCoordinate newCenter(static_cast<double>(orbitStatus.x) / qPow(10.0, 7.0), static_cast<double>(orbitStatus.y) / qPow(10.0, 7.0));
        if (_orbitMapCircle.center() != newCenter) {
            _orbitMapCircle.setCenter(newCenter);
        }
    
        if (!_orbitActive) {
            _orbitActive = true;
            _orbitMapCircle.setShowRotation(true);
            emit orbitActiveChanged(true);
        }
    
        _orbitTelemetryTimer.start(_orbitTelemetryTimeoutMsecs);
    }
    
    void Vehicle::_orbitTelemetryTimeout(void)
    {
        _orbitActive = false;
        emit orbitActiveChanged(false);
    }
    
    
    void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message)
    {
        mavlink_camera_image_captured_t feedback;
    
        mavlink_msg_camera_image_captured_decode(&message, &feedback);
    
        QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lon / qPow(10.0, 7.0), feedback.alt);
        qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.image_index << feedback.capture_result;
        if (feedback.capture_result == 1) {
            _cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
        }
    }
    
    
    Don Gagne's avatar
     
    Don Gagne committed
    void Vehicle::_handleStatusText(mavlink_message_t& message, bool longVersion)
    
    Don Gagne's avatar
     
    Don Gagne committed
    {
    
    Don Gagne's avatar
     
    Don Gagne committed
        QByteArray  b;
        QString     messageText;
        int         severity;
    
        if (longVersion) {
            b.resize(MAVLINK_MSG_STATUSTEXT_LONG_FIELD_TEXT_LEN+1);
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
            mavlink_statustext_long_t statustextLong;
            mavlink_msg_statustext_long_decode(&message, &statustextLong);
            strncpy(b.data(), statustextLong.text, MAVLINK_MSG_STATUSTEXT_LONG_FIELD_TEXT_LEN);
            severity = statustextLong.severity;
    
    Don Gagne's avatar
     
    Don Gagne committed
        } else {
            b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
            mavlink_statustext_t statustext;
            mavlink_msg_statustext_decode(&message, &statustext);
            strncpy(b.data(), statustext.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
            severity = statustext.severity;
    
    Don Gagne's avatar
     
    Don Gagne committed
        }
    
    Don Gagne's avatar
     
    Don Gagne committed
        b[b.length()-1] = '\0';
    
    Don Gagne's avatar
     
    Don Gagne committed
        messageText = QString(b);
    
    Don Gagne's avatar
     
    Don Gagne committed
    
        bool skipSpoken = false;
    
    Don Gagne's avatar
     
    Don Gagne committed
        bool ardupilotPrearm = messageText.startsWith(QStringLiteral("PreArm"));
    
    Don Gagne's avatar
     
    Don Gagne committed
        bool px4Prearm = messageText.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive) && severity >= MAV_SEVERITY_CRITICAL;
    
    Don Gagne's avatar
     
    Don Gagne committed
        if (ardupilotPrearm || px4Prearm) {
    
    Don Gagne's avatar
     
    Don Gagne committed
            // Limit repeated PreArm message to once every 10 seconds
            if (_noisySpokenPrearmMap.contains(messageText) && _noisySpokenPrearmMap[messageText].msecsTo(QTime::currentTime()) < (10 * 1000)) {
                skipSpoken = true;
            } else {
                _noisySpokenPrearmMap[messageText] = QTime::currentTime();
                setPrearmError(messageText);
            }
        }
    
    
        // If the message is NOTIFY or higher severity, or starts with a '#',
        // then read it aloud.
        if (messageText.startsWith("#") || severity <= MAV_SEVERITY_NOTICE) {
            messageText.remove("#");
            if (!skipSpoken) {
                qgcApp()->toolbox()->audioOutput()->say(messageText);
            }
        }
        emit textMessageReceived(id(), message.compid, severity, messageText);
    }
    
    
    void Vehicle::_handleVfrHud(mavlink_message_t& message)
    {
        mavlink_vfr_hud_t vfrHud;
        mavlink_msg_vfr_hud_decode(&message, &vfrHud);
    
        _airSpeedFact.setRawValue(qIsNaN(vfrHud.airspeed) ? 0 : vfrHud.airspeed);
        _groundSpeedFact.setRawValue(qIsNaN(vfrHud.groundspeed) ? 0 : vfrHud.groundspeed);
        _climbRateFact.setRawValue(qIsNaN(vfrHud.climb) ? 0 : vfrHud.climb);
    
    Don Gagne's avatar
     
    Don Gagne committed
        _throttlePctFact.setRawValue(vfrHud.throttle);
    
    void Vehicle::_handleEstimatorStatus(mavlink_message_t& message)
    {
        mavlink_estimator_status_t estimatorStatus;
        mavlink_msg_estimator_status_decode(&message, &estimatorStatus);
    
        _estimatorStatusFactGroup.goodAttitudeEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_ATTITUDE));
        _estimatorStatusFactGroup.goodHorizVelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_VELOCITY_HORIZ));
        _estimatorStatusFactGroup.goodVertVelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_VELOCITY_VERT));
        _estimatorStatusFactGroup.goodHorizPosRelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_HORIZ_REL));
        _estimatorStatusFactGroup.goodHorizPosAbsEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_HORIZ_ABS));
        _estimatorStatusFactGroup.goodVertPosAbsEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_VERT_ABS));
        _estimatorStatusFactGroup.goodVertPosAGLEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_VERT_AGL));
        _estimatorStatusFactGroup.goodConstPosModeEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_CONST_POS_MODE));
        _estimatorStatusFactGroup.goodPredHorizPosRelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_PRED_POS_HORIZ_REL));
        _estimatorStatusFactGroup.goodPredHorizPosAbsEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_PRED_POS_HORIZ_ABS));
        _estimatorStatusFactGroup.gpsGlitch()->setRawValue(estimatorStatus.flags & ESTIMATOR_GPS_GLITCH ? true : false);
        _estimatorStatusFactGroup.accelError()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_ACCEL_ERROR));
        _estimatorStatusFactGroup.velRatio()->setRawValue(estimatorStatus.vel_ratio);
        _estimatorStatusFactGroup.horizPosRatio()->setRawValue(estimatorStatus.pos_horiz_ratio);
        _estimatorStatusFactGroup.vertPosRatio()->setRawValue(estimatorStatus.pos_vert_ratio);
        _estimatorStatusFactGroup.magRatio()->setRawValue(estimatorStatus.mag_ratio);
        _estimatorStatusFactGroup.haglRatio()->setRawValue(estimatorStatus.hagl_ratio);
        _estimatorStatusFactGroup.tasRatio()->setRawValue(estimatorStatus.tas_ratio);
        _estimatorStatusFactGroup.horizPosAccuracy()->setRawValue(estimatorStatus.pos_horiz_accuracy);
        _estimatorStatusFactGroup.vertPosAccuracy()->setRawValue(estimatorStatus.pos_vert_accuracy);
    
    #if 0