Skip to content
Snippets Groups Projects
Vehicle.cc 76.6 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.
     *
     ****************************************************************************/
    
    
    #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"
    
    #include "GeoFenceManager.h"
    #include "RallyPointManager.h"
    
    #include "CoordinateVector.h"
    
    #include "ParameterManager.h"
    
    #include "QGCApplication.h"
    
    dogmaphobic's avatar
    dogmaphobic committed
    #include "QGCImageProvider.h"
    
    #include "GAudioOutput.h"
    
    Jimmy Johnson's avatar
    Jimmy Johnson committed
    #include "FollowMe.h"
    
    #include "MissionCommandTree.h"
    
    #include "QGroundControlQmlGlobal.h"
    
    
    QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
    
    
    #define UPDATE_TIMER 50
    #define DEFAULT_LAT  38.965767f
    #define DEFAULT_LON -120.083923f
    
    
    extern const char* 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";
    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";
    
    Don Gagne's avatar
    Don Gagne committed
    
    const char* Vehicle::_gpsFactGroupName =        "gps";
    const char* Vehicle::_batteryFactGroupName =    "battery";
    
    Don Gagne's avatar
    Don Gagne committed
    const char* Vehicle::_windFactGroupName =       "wind";
    
    const char* Vehicle::_vibrationFactGroupName =  "vibration";
    
    const int Vehicle::_lowBatteryAnnounceRepeatMSecs = 30 * 1000;
    
    Vehicle::Vehicle(LinkInterface*             link,
                     int                        vehicleId,
                     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)
    
        , _active(false)
    
        , _offlineEditingVehicle(false)
    
        , _firmwareType(firmwareType)
    
        , _vehicleType(vehicleType)
    
        , _firmwarePlugin(NULL)
    
        , _firmwarePluginInstanceData(NULL)
    
        , _autopilotPlugin(NULL)
    
        , _mavlink(NULL)
        , _soloFirmware(false)
    
        , _joystickMode(JoystickModeRC)
    
        , _joystickEnabled(false)
    
        , _uas(NULL)
    
        , _coordinate(37.803784, -122.462276)
        , _coordinateValid(false)
    
        , _homePositionAvailable(false)
    
        , _mav(NULL)
        , _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)
    
        , _onboardControlSensorsPresent(0)
        , _onboardControlSensorsEnabled(0)
        , _onboardControlSensorsHealth(0)
        , _onboardControlSensorsUnhealthy(0)
    
        , _useGpsRawIntForPosition(true)
        , _useGpsRawIntForAltitude(true)
        , _useAltitudeForAltitude(false)
    
        , _connectionLost(false)
        , _connectionLostEnabled(true)
    
        , _missionManager(NULL)
    
        , _missionManagerInitialRequestSent(false)
    
        , _geoFenceManager(NULL)
    
        , _geoFenceManagerInitialRequestSent(false)
        , _rallyPointManager(NULL)
        , _rallyPointManagerInitialRequestSent(false)
    
    Don Gagne's avatar
    Don Gagne committed
        , _armed(false)
        , _base_mode(0)
        , _custom_mode(0)
    
        , _nextSendMessageMultipleIndex(0)
    
        , _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)
    
        , _firmwareVersionType(FIRMWARE_VERSION_TYPE_OFFICIAL)
    
    Don Gagne's avatar
    Don Gagne committed
        , _rollFact             (0, _rollFactName,              FactMetaData::valueTypeDouble)
        , _pitchFact            (0, _pitchFactName,             FactMetaData::valueTypeDouble)
        , _headingFact          (0, _headingFactName,           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)
        , _gpsFactGroup(this)
    
    Don Gagne's avatar
    Don Gagne committed
        , _batteryFactGroup(this)
    
    Don Gagne's avatar
    Don Gagne committed
        , _windFactGroup(this)
    
        , _vibrationFactGroup(this)
    
    {
        _addLink(link);
    
        _mavlink = qgcApp()->toolbox()->mavlinkProtocol();
    
    dogmaphobic's avatar
    dogmaphobic committed
        connect(_mavlink, &MAVLinkProtocol::messageReceived,     this, &Vehicle::_mavlinkMessageReceived);
    
        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);
    
        _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);
    
    dogmaphobic's avatar
    dogmaphobic committed
    
        _firmwarePlugin     = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
    
        _autopilotPlugin    = _firmwarePlugin->autopilotPlugin(this);
    
    Jimmy Johnson's avatar
    Jimmy Johnson committed
        // connect this vehicle to the follow me handle manager
        connect(this, &Vehicle::flightModeChanged,qgcApp()->toolbox()->followMe(), &FollowMe::followMeHandleManager);
    
    
    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);
    
    
        // Connection Lost timer
        _connectionLostTimer.setInterval(_connectionLostTimeoutMSecs);
    
        _connectionLostTimer.setSingleShot(false);
        _connectionLostTimer.start();
        connect(&_connectionLostTimer, &QTimer::timeout, this, &Vehicle::_connectionLostTimeout);
    
        // Send MAV_CMD ack timer
        _mavCommandAckTimer.setSingleShot(true);
        _mavCommandAckTimer.setInterval(_mavCommandAckTimeoutMSecs);
        connect(&_mavCommandAckTimer, &QTimer::timeout, this, &Vehicle::_sendMavCommandAgain);
    
    
        // Listen for system messages
    
    dogmaphobic's avatar
    dogmaphobic committed
        connect(qgcApp()->toolbox()->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged,  this, &Vehicle::_handleTextMessage);
        connect(qgcApp()->toolbox()->uasMessageHandler(), &UASMessageHandler::textMessageReceived,      this, &Vehicle::_handletextMessageReceived);
    
        // Now connect the new UAS
        connect(_mav, SIGNAL(attitudeChanged                    (UASInterface*,double,double,double,quint64)),              this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64)));
        connect(_mav, SIGNAL(attitudeChanged                    (UASInterface*,int,double,double,double,quint64)),          this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64)));
        connect(_mav, SIGNAL(statusChanged                      (UASInterface*,QString,QString)),                           this, SLOT(_updateState(UASInterface*, QString,QString)));
    
        _loadSettings();
    
        _missionManager = new MissionManager(this);
    
        connect(_missionManager, &MissionManager::error,                    this, &Vehicle::_missionManagerError);
        connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_newMissionItemsAvailable);
    
    
        _parameterManager = new ParameterManager(this);
        connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
    
        // GeoFenceManager needs to access ParameterManager so make sure to create after
    
        _geoFenceManager = _firmwarePlugin->newGeoFenceManager(this);
        connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
    
        connect(_geoFenceManager, &GeoFenceManager::loadComplete, this, &Vehicle::_newGeoFenceAvailable);
    
        _rallyPointManager = _firmwarePlugin->newRallyPointManager(this);
        connect(_rallyPointManager, &RallyPointManager::error, this, &Vehicle::_rallyPointManagerError);
    
        // Ask the vehicle for firmware version info.
        sendMavCommand(MAV_COMP_ID_ALL,                         // Don't know default component id yet.
                        MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
                       false,                                   // No error shown if fails
                        1);                                     // Request firmware version
    
        _firmwarePlugin->initializeVehicle(this);
    
        _sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay);
        connect(&_sendMultipleTimer, &QTimer::timeout, this, &Vehicle::_sendMessageMultipleNext);
    
        _mapTrajectoryTimer.setInterval(_mapTrajectoryMsecsBetweenPoints);
        connect(&_mapTrajectoryTimer, &QTimer::timeout, this, &Vehicle::_addNewMapTrajectoryPoint);
    
        // Invalidate the timer to signal first announce
        _lowBatteryAnnounceTimer.invalidate();
    
    
    Don Gagne's avatar
    Don Gagne committed
        // Build FactGroup object model
    
        _addFact(&_rollFact,                _rollFactName);
        _addFact(&_pitchFact,               _pitchFactName);
        _addFact(&_headingFact,             _headingFactName);
        _addFact(&_groundSpeedFact,         _groundSpeedFactName);
        _addFact(&_airSpeedFact,            _airSpeedFactName);
        _addFact(&_climbRateFact,           _climbRateFactName);
        _addFact(&_altitudeRelativeFact,    _altitudeRelativeFactName);
        _addFact(&_altitudeAMSLFact,        _altitudeAMSLFactName);
    
    
    Don Gagne's avatar
    Don Gagne committed
        _addFactGroup(&_gpsFactGroup,       _gpsFactGroupName);
        _addFactGroup(&_batteryFactGroup,   _batteryFactGroupName);
    
    Don Gagne's avatar
    Don Gagne committed
        _addFactGroup(&_windFactGroup,      _windFactGroupName);
    
        _addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName);
    
    Don Gagne's avatar
    Don Gagne committed
        _gpsFactGroup.setVehicle(this);
    
    Don Gagne's avatar
    Don Gagne committed
        _batteryFactGroup.setVehicle(this);
    
    Don Gagne's avatar
    Don Gagne committed
        _windFactGroup.setVehicle(this);
    
        _vibrationFactGroup.setVehicle(this);
    
    // 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)
        , _active(false)
    
        , _offlineEditingVehicle(true)
    
        , _firmwareType(firmwareType)
        , _vehicleType(vehicleType)
    
        , _firmwarePlugin(NULL)
    
        , _firmwarePluginInstanceData(NULL)
    
        , _autopilotPlugin(NULL)
        , _joystickMode(JoystickModeRC)
        , _joystickEnabled(false)
        , _uas(NULL)
        , _coordinate(37.803784, -122.462276)
        , _coordinateValid(false)
        , _homePositionAvailable(false)
        , _mav(NULL)
        , _currentMessageCount(0)
        , _messageCount(0)
        , _currentErrorCount(0)
        , _currentWarningCount(0)
        , _currentNormalCount(0)
        , _currentMessageType(MessageNone)
        , _updateCount(0)
    
        , _rcRSSI(255)
        , _rcRSSIstore(255)
    
        , _autoDisconnect(false)
    
        , _flying(false)
        , _onboardControlSensorsPresent(0)
        , _onboardControlSensorsEnabled(0)
        , _onboardControlSensorsHealth(0)
        , _onboardControlSensorsUnhealthy(0)
    
        , _useGpsRawIntForPosition(true)
        , _useGpsRawIntForAltitude(true)
        , _useAltitudeForAltitude(false)
    
        , _connectionLost(false)
        , _connectionLostEnabled(true)
        , _missionManager(NULL)
    
        , _missionManagerInitialRequestSent(false)
    
        , _geoFenceManager(NULL)
    
        , _geoFenceManagerInitialRequestSent(false)
        , _rallyPointManager(NULL)
        , _rallyPointManagerInitialRequestSent(false)
    
        , _armed(false)
        , _base_mode(0)
        , _custom_mode(0)
        , _nextSendMessageMultipleIndex(0)
    
        , _firmwarePluginManager(firmwarePluginManager)
    
        , _joystickManager(NULL)
        , _flowImageIndex(0)
        , _allLinksInactiveSent(false)
        , _messagesReceived(0)
        , _messagesSent(0)
        , _messagesLost(0)
        , _messageSeq(0)
        , _compID(0)
        , _heardFrom(false)
    
        , _firmwareMajorVersion(versionNotSetValue)
        , _firmwareMinorVersion(versionNotSetValue)
        , _firmwarePatchVersion(versionNotSetValue)
    
        , _rollFact             (0, _rollFactName,              FactMetaData::valueTypeDouble)
        , _pitchFact            (0, _pitchFactName,             FactMetaData::valueTypeDouble)
        , _headingFact          (0, _headingFactName,           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)
        , _gpsFactGroup(this)
        , _batteryFactGroup(this)
        , _windFactGroup(this)
        , _vibrationFactGroup(this)
    {
    
        _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
    
        _firmwarePlugin->initializeVehicle(this);
    
    
        _missionManager = new MissionManager(this);
        connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
    
    
        _parameterManager = new ParameterManager(this);
    
        // GeoFenceManager needs to access ParameterManager so make sure to create after
    
        _geoFenceManager = _firmwarePlugin->newGeoFenceManager(this);
        connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
    
        _rallyPointManager = _firmwarePlugin->newRallyPointManager(this);
        connect(_rallyPointManager, &RallyPointManager::error, this, &Vehicle::_rallyPointManagerError);
    
    
        // Build FactGroup object model
    
        _addFact(&_rollFact,                _rollFactName);
        _addFact(&_pitchFact,               _pitchFactName);
        _addFact(&_headingFact,             _headingFactName);
        _addFact(&_groundSpeedFact,         _groundSpeedFactName);
        _addFact(&_airSpeedFact,            _airSpeedFactName);
        _addFact(&_climbRateFact,           _climbRateFactName);
        _addFact(&_altitudeRelativeFact,    _altitudeRelativeFactName);
        _addFact(&_altitudeAMSLFact,        _altitudeAMSLFactName);
    
        _addFactGroup(&_gpsFactGroup,       _gpsFactGroupName);
        _addFactGroup(&_batteryFactGroup,   _batteryFactGroupName);
        _addFactGroup(&_windFactGroup,      _windFactGroupName);
        _addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName);
    
        _gpsFactGroup.setVehicle(NULL);
        _batteryFactGroup.setVehicle(NULL);
        _windFactGroup.setVehicle(NULL);
        _vibrationFactGroup.setVehicle(NULL);
    }
    
    
    Vehicle::~Vehicle()
    {
    
    Don Gagne's avatar
    Don Gagne committed
        qCDebug(VehicleLog) << "~Vehicle" << this;
    
    
        delete _missionManager;
        _missionManager = NULL;
    
        delete _autopilotPlugin;
        _autopilotPlugin = NULL;
    
    
        delete _mav;
        _mav = NULL;
    
    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 (message.sysid != _id && message.sysid != 0) {
    
        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) {
                uint16_t seq_received = (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;
        }
    
    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_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_AUTOPILOT_VERSION:
    
    Gus Grubba's avatar
    Gus Grubba committed
            _handleAutopilotVersion(link, message);
    
        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;
    
    Don Gagne's avatar
    Don Gagne committed
    
        // Following are ArduPilot dialect messages
    
        case MAVLINK_MSG_ID_WIND:
            _handleWind(message);
            break;
    
    Don Gagne's avatar
    Don Gagne committed
        emit mavlinkMessageReceived(message);
    
        _uas->receiveMessage(message);
    }
    
    
    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);
    }
    
    void Vehicle::_handleGpsRawInt(mavlink_message_t& message)
    {
        mavlink_gps_raw_int_t gpsRawInt;
        mavlink_msg_gps_raw_int_decode(&message, &gpsRawInt);
    
        if (gpsRawInt.fix_type >= GPS_FIX_TYPE_3D_FIX) {
            if (_useGpsRawIntForPosition) {
                setLatitude(gpsRawInt.lat / (double)1E7);
                setLongitude(gpsRawInt.lon / (double)1E7);
            }
            if (_useGpsRawIntForAltitude) {
                _altitudeRelativeFact.setRawValue(gpsRawInt.alt / 1000.0);
            }
        }
    
        _gpsFactGroup.count()->setRawValue(gpsRawInt.satellites_visible == 255 ? 0 : gpsRawInt.satellites_visible);
        _gpsFactGroup.hdop()->setRawValue(gpsRawInt.eph == UINT16_MAX ? 1e10f : gpsRawInt.eph / 100.0);
        _gpsFactGroup.vdop()->setRawValue(gpsRawInt.epv == UINT16_MAX ? 1e10f : gpsRawInt.epv / 100.0);
        _gpsFactGroup.courseOverGround()->setRawValue(gpsRawInt.cog == UINT16_MAX ? 0.0 : gpsRawInt.cog / 100.0);
        _gpsFactGroup.lock()->setRawValue(gpsRawInt.fix_type);
    
        if (gpsRawInt.fix_type >= GPS_FIX_TYPE_3D_FIX) {
            _setCoordinateValid(true);
        }
    }
    
    void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
    {
        mavlink_global_position_int_t globalPositionInt;
        mavlink_msg_global_position_int_decode(&message, &globalPositionInt);
    
        _useGpsRawIntForPosition = false;
        _useGpsRawIntForAltitude = false;
    
        setLatitude(globalPositionInt.lat / (double)1E7);
        setLongitude(globalPositionInt.lon / (double)1E7);
        if (!_useAltitudeForAltitude) {
            _altitudeRelativeFact.setRawValue(globalPositionInt.relative_alt / 1000.0);
            _altitudeAMSLFact.setRawValue(globalPositionInt.alt / 1000.0);
        }
    }
    
    void Vehicle::_handleAltitude(mavlink_message_t& message)
    {
        mavlink_altitude_t altitude;
        mavlink_msg_altitude_decode(&message, &altitude);
    
        _useAltitudeForAltitude = true;
        _useGpsRawIntForAltitude = false;
    
    yaoling's avatar
    yaoling committed
        _altitudeRelativeFact.setRawValue(altitude.altitude_relative);
        _altitudeAMSLFact.setRawValue(altitude.altitude_amsl);
    
    Gus Grubba's avatar
    Gus Grubba committed
    void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& message)
    
    {
        mavlink_autopilot_version_t autopilotVersion;
        mavlink_msg_autopilot_version_decode(&message, &autopilotVersion);
    
    
    Gus Grubba's avatar
    Gus Grubba committed
        bool isMavlink2 = (autopilotVersion.capabilities & MAV_PROTOCOL_CAPABILITY_MAVLINK2) != 0;
        if(isMavlink2) {
            mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(link->mavlinkChannel());
            mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
        }
    
    
        if (autopilotVersion.flight_sw_version != 0) {
            int majorVersion, minorVersion, patchVersion;
            FIRMWARE_VERSION_TYPE versionType;
    
            majorVersion = (autopilotVersion.flight_sw_version >> (8*3)) & 0xFF;
            minorVersion = (autopilotVersion.flight_sw_version >> (8*2)) & 0xFF;
            patchVersion = (autopilotVersion.flight_sw_version >> (8*1)) & 0xFF;
            versionType = (FIRMWARE_VERSION_TYPE)((autopilotVersion.flight_sw_version >> (8*0)) & 0xFF);
    
    Don Gagne's avatar
    Don Gagne committed
            setFirmwareVersion(majorVersion, minorVersion, patchVersion, versionType);
    
    void Vehicle::_handleHilActuatorControls(mavlink_message_t &message)
    {
        mavlink_hil_actuator_controls_t hil;
        mavlink_msg_hil_actuator_controls_decode(&message, &hil);
        emit hilActuatorControlsChanged(hil.time_usec, hil.flags,
                                        hil.controls[0],
                                        hil.controls[1],
                                        hil.controls[2],
                                        hil.controls[3],
                                        hil.controls[4],
                                        hil.controls[5],
                                        hil.controls[6],
                                        hil.controls[7],
                                        hil.controls[8],
                                        hil.controls[9],
                                        hil.controls[10],
                                        hil.controls[11],
                                        hil.controls[12],
                                        hil.controls[13],
                                        hil.controls[14],
                                        hil.controls[15],
                                        hil.mode);
    }
    
    
    void Vehicle::_handleCommandAck(mavlink_message_t& message)
    {
    
        mavlink_command_ack_t ack;
        mavlink_msg_command_ack_decode(&message, &ack);
    
    
        if (_mavCommandQueue.count() && ack.command == _mavCommandQueue[0].command) {
    
    Don Gagne's avatar
    Don Gagne committed
            _mavCommandAckTimer.stop();
    
            showError = _mavCommandQueue[0].showError;
            _mavCommandQueue.removeFirst();
        }
    
    
    Don Gagne's avatar
    Don Gagne committed
        emit mavCommandResult(_id, message.compid, ack.command, ack.result, false /* noResponsefromVehicle */);
    
    
        if (showError) {
            QString commandName = qgcApp()->toolbox()->missionCommandTree()->friendlyName((MAV_CMD)ack.command);
    
            switch (ack.result) {
            case MAV_RESULT_TEMPORARILY_REJECTED:
                qgcApp()->showMessage(tr("%1 command temporarily rejected").arg(commandName));
                break;
            case MAV_RESULT_DENIED:
                qgcApp()->showMessage(tr("%1 command denied").arg(commandName));
                break;
            case MAV_RESULT_UNSUPPORTED:
                qgcApp()->showMessage(tr("%1 command not supported").arg(commandName));
                break;
            case MAV_RESULT_FAILED:
                qgcApp()->showMessage(tr("%1 command failed").arg(commandName));
                break;
    
        _sendNextQueuedMavCommand();
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::_handleExtendedSysState(mavlink_message_t& message)
    {
        mavlink_extended_sys_state_t extendedState;
        mavlink_msg_extended_sys_state_decode(&message, &extendedState);
    
        switch (extendedState.landed_state) {
    
    Don Gagne's avatar
    Don Gagne committed
        case MAV_LANDED_STATE_UNDEFINED:
    
    Don Gagne's avatar
    Don Gagne committed
            break;
        case MAV_LANDED_STATE_ON_GROUND:
            setFlying(false);
            break;
        case MAV_LANDED_STATE_IN_AIR:
            setFlying(true);
            return;
        }
    }
    
    
    void Vehicle::_handleVibration(mavlink_message_t& message)
    {
        mavlink_vibration_t vibration;
        mavlink_msg_vibration_decode(&message, &vibration);
    
        _vibrationFactGroup.xAxis()->setRawValue(vibration.vibration_x);
        _vibrationFactGroup.yAxis()->setRawValue(vibration.vibration_y);
        _vibrationFactGroup.zAxis()->setRawValue(vibration.vibration_z);
        _vibrationFactGroup.clipCount1()->setRawValue(vibration.clipping_0);
        _vibrationFactGroup.clipCount2()->setRawValue(vibration.clipping_1);
        _vibrationFactGroup.clipCount3()->setRawValue(vibration.clipping_2);
    }
    
    
    void Vehicle::_handleWindCov(mavlink_message_t& message)
    {
        mavlink_wind_cov_t wind;
        mavlink_msg_wind_cov_decode(&message, &wind);
    
        float direction = qRadiansToDegrees(qAtan2(wind.wind_y, wind.wind_x));
        float speed = qSqrt(qPow(wind.wind_x, 2) + qPow(wind.wind_y, 2));
    
        _windFactGroup.direction()->setRawValue(direction);
        _windFactGroup.speed()->setRawValue(speed);
        _windFactGroup.verticalSpeed()->setRawValue(0);
    }
    
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::_handleWind(mavlink_message_t& message)
    {
        mavlink_wind_t wind;
        mavlink_msg_wind_decode(&message, &wind);
    
        _windFactGroup.direction()->setRawValue(wind.direction);
        _windFactGroup.speed()->setRawValue(wind.speed);
        _windFactGroup.verticalSpeed()->setRawValue(wind.speed_z);
    }
    
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::_handleSysStatus(mavlink_message_t& message)
    {
        mavlink_sys_status_t sysStatus;
        mavlink_msg_sys_status_decode(&message, &sysStatus);
    
        if (sysStatus.current_battery == -1) {
            _batteryFactGroup.current()->setRawValue(VehicleBatteryFactGroup::_currentUnavailable);
        } else {
    
            // Current is in Amps, current_battery is 10 * milliamperes (1 = 10 milliampere)
    
            _batteryFactGroup.current()->setRawValue((float)sysStatus.current_battery / 100.0f);
    
    Don Gagne's avatar
    Don Gagne committed
        }
        if (sysStatus.voltage_battery == UINT16_MAX) {
            _batteryFactGroup.voltage()->setRawValue(VehicleBatteryFactGroup::_voltageUnavailable);
        } else {
            _batteryFactGroup.voltage()->setRawValue((double)sysStatus.voltage_battery / 1000.0);
        }
        _batteryFactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining);
    
        if (sysStatus.battery_remaining > 0 && sysStatus.battery_remaining < QGroundControlQmlGlobal::batteryPercentRemainingAnnounce()->rawValue().toInt()) {
    
            if (!_lowBatteryAnnounceTimer.isValid() || _lowBatteryAnnounceTimer.elapsed() > _lowBatteryAnnounceRepeatMSecs) {
                _lowBatteryAnnounceTimer.restart();
    
                _say(QString("%1 low battery: %2 percent remaining").arg(_vehicleIdSpeech()).arg(sysStatus.battery_remaining));
    
    
        _onboardControlSensorsPresent = sysStatus.onboard_control_sensors_present;
        _onboardControlSensorsEnabled = sysStatus.onboard_control_sensors_enabled;
        _onboardControlSensorsHealth = sysStatus.onboard_control_sensors_health;
    
        uint32_t newSensorsUnhealthy = _onboardControlSensorsEnabled & ~_onboardControlSensorsHealth;
        if (newSensorsUnhealthy != _onboardControlSensorsUnhealthy) {
            _onboardControlSensorsUnhealthy = newSensorsUnhealthy;
            emit unhealthySensorsChanged();
        }
    
    Don Gagne's avatar
    Don Gagne committed
    }
    
    void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
    {
        mavlink_battery_status_t bat_status;
        mavlink_msg_battery_status_decode(&message, &bat_status);
    
        if (bat_status.temperature == INT16_MAX) {
            _batteryFactGroup.temperature()->setRawValue(VehicleBatteryFactGroup::_temperatureUnavailable);
        } else {
            _batteryFactGroup.temperature()->setRawValue((double)bat_status.temperature / 100.0);
        }
        if (bat_status.current_consumed == -1) {
            _batteryFactGroup.mahConsumed()->setRawValue(VehicleBatteryFactGroup::_mahConsumedUnavailable);
        } else {
            _batteryFactGroup.mahConsumed()->setRawValue(bat_status.current_consumed);
        }
    
        int cellCount = 0;
        for (int i=0; i<10; i++) {
            if (bat_status.voltages[i] != UINT16_MAX) {
                cellCount++;
            }
        }
        if (cellCount == 0) {
            cellCount = -1;
        }
    
        _batteryFactGroup.cellCount()->setRawValue(cellCount);
    }
    
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::_handleHomePosition(mavlink_message_t& message)
    {
    
    Don Gagne's avatar
    Don Gagne committed
        bool emitHomePositionChanged =          false;
        bool emitHomePositionAvailableChanged = false;
    
    
    Don Gagne's avatar
    Don Gagne committed
        mavlink_home_position_t homePos;
    
    Don Gagne's avatar
    Don Gagne committed
        mavlink_msg_home_position_decode(&message, &homePos);
    
    Don Gagne's avatar
    Don Gagne committed
    
        QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0,
                                        homePos.longitude / 10000000.0,
                                        homePos.altitude / 1000.0);
    
    Don Gagne's avatar
    Don Gagne committed
        if (!_homePositionAvailable || newHomePosition != _homePosition) {
    
    Don Gagne's avatar
    Don Gagne committed
            emitHomePositionChanged = true;
            _homePosition = newHomePosition;
        }
    
        if (!_homePositionAvailable) {
            emitHomePositionAvailableChanged = true;
    
    Don Gagne's avatar
    Don Gagne committed
            _homePositionAvailable = true;
    
    Don Gagne's avatar
    Don Gagne committed
        }
    
        if (emitHomePositionChanged) {
    
    Don Gagne's avatar
    Don Gagne committed
            qCDebug(VehicleLog) << "New home position" << newHomePosition;
    
            qgcApp()->setLastKnownHomePosition(_homePosition);
    
    Don Gagne's avatar
    Don Gagne committed
            emit homePositionChanged(_homePosition);
        }
        if (emitHomePositionAvailableChanged) {
            emit homePositionAvailableChanged(true);
        }
    
    Don Gagne's avatar
    Don Gagne committed
    }
    
    void Vehicle::_handleHeartbeat(mavlink_message_t& message)
    {
    
        _connectionActive();
    
    
    Don Gagne's avatar
    Don Gagne committed
        mavlink_heartbeat_t heartbeat;
    
    Don Gagne's avatar
    Don Gagne committed
        mavlink_msg_heartbeat_decode(&message, &heartbeat);
    
    Don Gagne's avatar
    Don Gagne committed
        bool newArmed = heartbeat.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
    
    Don Gagne's avatar
    Don Gagne committed
        if (_armed != newArmed) {
            _armed = newArmed;
            emit armedChanged(_armed);
    
            // We are transitioning to the armed state, begin tracking trajectory points for the map
            if (_armed) {
                _mapTrajectoryStart();
            } else {
                _mapTrajectoryStop();
            }
    
    Don Gagne's avatar
    Don Gagne committed
        }
    
        if (heartbeat.base_mode != _base_mode || heartbeat.custom_mode != _custom_mode) {
            _base_mode = heartbeat.base_mode;
            _custom_mode = heartbeat.custom_mode;
            emit flightModeChanged(flightMode());
        }
    }
    
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::_handleRCChannels(mavlink_message_t& message)
    {
        mavlink_rc_channels_t channels;
    
        mavlink_msg_rc_channels_decode(&message, &channels);
    
        uint16_t* _rgChannelvalues[cMaxRcChannels] = {
            &channels.chan1_raw,
            &channels.chan2_raw,
            &channels.chan3_raw,
            &channels.chan4_raw,
            &channels.chan5_raw,
            &channels.chan6_raw,
            &channels.chan7_raw,
            &channels.chan8_raw,
            &channels.chan9_raw,
            &channels.chan10_raw,
            &channels.chan11_raw,
            &channels.chan12_raw,
            &channels.chan13_raw,
            &channels.chan14_raw,
            &channels.chan15_raw,
            &channels.chan16_raw,
            &channels.chan17_raw,
            &channels.chan18_raw,
        };
        int pwmValues[cMaxRcChannels];
    
        for (int i=0; i<cMaxRcChannels; i++) {
            uint16_t channelValue = *_rgChannelvalues[i];
    
            if (i < channels.chancount) {
                pwmValues[i] = channelValue == UINT16_MAX ? -1 : channelValue;
            } else {
                pwmValues[i] = -1;
            }
        }
    
        emit remoteControlRSSIChanged(channels.rssi);
        emit rcChannelsChanged(channels.chancount, pwmValues);
    }
    
    void Vehicle::_handleRCChannelsRaw(mavlink_message_t& message)
    {
        // We handle both RC_CHANNLES and RC_CHANNELS_RAW since different firmware will only
        // send one or the other.
    
        mavlink_rc_channels_raw_t channels;
    
        mavlink_msg_rc_channels_raw_decode(&message, &channels);
    
        uint16_t* _rgChannelvalues[cMaxRcChannels] = {
            &channels.chan1_raw,
            &channels.chan2_raw,
            &channels.chan3_raw,
            &channels.chan4_raw,
            &channels.chan5_raw,
            &channels.chan6_raw,
            &channels.chan7_raw,
            &channels.chan8_raw,
        };
    
        int pwmValues[cMaxRcChannels];
        int channelCount = 0;
    
    
    Don Gagne's avatar
    Don Gagne committed
        for (int i=0; i<cMaxRcChannels; i++) {
            pwmValues[i] = -1;
        }
    
    
    Don Gagne's avatar
    Don Gagne committed
        for (int i=0; i<8; i++) {
            uint16_t channelValue = *_rgChannelvalues[i];
    
            if (channelValue == UINT16_MAX) {
                pwmValues[i] = -1;
            } else {
    
    Don Gagne's avatar
    Don Gagne committed
                channelCount = i + 1;
    
    Don Gagne's avatar
    Don Gagne committed
                pwmValues[i] = channelValue;
            }
        }
        for (int i=9; i<18; i++) {
            pwmValues[i] = -1;
        }
    
        emit remoteControlRSSIChanged(channels.rssi);
        emit rcChannelsChanged(channelCount, pwmValues);
    }
    
    
    bool Vehicle::_containsLink(LinkInterface* link)
    {
    
    Don Gagne's avatar
    Don Gagne committed
        return _links.contains(link);
    
    }
    
    void Vehicle::_addLink(LinkInterface* link)
    {
        if (!_containsLink(link)) {
    
    Don Gagne's avatar
    Don Gagne committed
            _links += link;
    
            qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((ulong)link, 0, 16);
    
    Don Gagne's avatar
    Don Gagne committed
            connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
            connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDeleted, this, &Vehicle::_linkInactiveOrDeleted);
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::_linkInactiveOrDeleted(LinkInterface* link)
    
    Don Gagne's avatar
    Don Gagne committed
        qCDebug(VehicleLog) << "_linkInactiveOrDeleted linkCount" << _links.count();
    
    Don Gagne's avatar
    Don Gagne committed
        _links.removeOne(link);
    
    Don Gagne's avatar
    Don Gagne committed
        if (_links.count() == 0 && !_allLinksInactiveSent) {
    
    Don Gagne's avatar
    Don Gagne committed
            qCDebug(VehicleLog) << "All links inactive";
    
    Don Gagne's avatar
    Don Gagne committed
            // Make sure to not send this more than one time
            _allLinksInactiveSent = true;
            emit allLinksInactive(this);
    
    bool Vehicle::sendMessageOnLink(LinkInterface* link, mavlink_message_t message)
    {
        if (!link || !_links.contains(link) || !link->isConnected()) {
            return false;
        }
    
        emit _sendMessageOnLinkOnThread(link, message);
    
        return true;
    }
    
    void Vehicle::_sendMessageOnLink(LinkInterface* link, mavlink_message_t message)
    {
    
        // Make sure this is still a good link
        if (!link || !_links.contains(link) || !link->isConnected()) {
            return;
        }
    
    
    #if 0
        // Leaving in for ease in Mav 2.0 testing
        mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(link->mavlinkChannel());
        qDebug() << "_sendMessageOnLink" << mavlinkStatus << link->mavlinkChannel() << mavlinkStatus->flags << message.magic;
    #endif
    
    
        // Give the plugin a chance to adjust
    
        _firmwarePlugin->adjustOutgoingMavlinkMessage(this, link, &message);
    
    Don Gagne's avatar
    Don Gagne committed
    
        // Write message into buffer, prepending start sign
        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
        int len = mavlink_msg_to_send_buffer(buffer, &message);
    
        link->writeBytesSafe((const char*)buffer, len);
    
        _messagesSent++;
        emit messagesSentChanged();
    
    }
    
    /// @return Direct usb connection link to board if one, NULL if none
    LinkInterface* Vehicle::priorityLink(void)
    {
    
    Gus Grubba's avatar
    Gus Grubba committed
    #ifndef NO_SERIAL_LINK
    
        foreach (LinkInterface* link, _links) {
            if (link->isConnected()) {
                SerialLink* pSerialLink = qobject_cast<SerialLink*>(link);
                if (pSerialLink) {
                    LinkConfiguration* pLinkConfig = pSerialLink->getLinkConfiguration();
                    if (pLinkConfig) {
                        SerialConfiguration* pSerialConfig = qobject_cast<SerialConfiguration*>(pLinkConfig);
                        if (pSerialConfig && pSerialConfig->usbDirect()) {
                            return link;
                        }
                    }