Skip to content
Snippets Groups Projects
Vehicle.cc 64.2 KiB
Newer Older
  • Learn to ignore specific revisions
  •     normalCount += pMh->getNormalCount();
        //-- See if we have a higher level
        if(errorCount != _currentErrorCount) {
            _currentErrorCount = errorCount;
            type = MessageError;
        }
        if(warnCount != _currentWarningCount) {
            _currentWarningCount = warnCount;
            if(_currentMessageType != MessageError) {
                type = MessageWarning;
            }
        }
        if(normalCount != _currentNormalCount) {
            _currentNormalCount = normalCount;
            if(_currentMessageType != MessageError && _currentMessageType != MessageWarning) {
                type = MessageNormal;
            }
        }
        int count = _currentErrorCount + _currentWarningCount + _currentNormalCount;
        if(count != _currentMessageCount) {
            _currentMessageCount = count;
            // Display current total new messages count
            emit newMessageCountChanged();
        }
        if(type != _currentMessageType) {
            _currentMessageType = type;
            // Update message level
            emit messageTypeChanged();
        }
        // Update message count (all messages)
        if(newCount != _messageCount) {
            _messageCount = newCount;
            emit messageCountChanged();
        }
        QString errMsg = pMh->getLatestError();
        if(errMsg != _latestError) {
            _latestError = errMsg;
            emit latestErrorChanged();
        }
    }
    
    void Vehicle::resetMessages()
    {
        // Reset Counts
        int count = _currentMessageCount;
        MessageType_t type = _currentMessageType;
        _currentErrorCount   = 0;
        _currentWarningCount = 0;
        _currentNormalCount  = 0;
        _currentMessageCount = 0;
        _currentMessageType = MessageNone;
        if(count != _currentMessageCount) {
            emit newMessageCountChanged();
        }
        if(type != _currentMessageType) {
            emit messageTypeChanged();
        }
    }
    
    
    int Vehicle::manualControlReservedButtonCount(void)
    {
        return _firmwarePlugin->manualControlReservedButtonCount();
    }
    
    void Vehicle::_loadSettings(void)
    {
        QSettings settings;
    
        settings.beginGroup(QString(_settingsGroup).arg(_id));
    
        _joystickMode = (JoystickMode_t)settings.value(_joystickModeSettingsKey, JoystickModeRC).toInt(&convertOk);
        if (!convertOk) {
            _joystickMode = JoystickModeRC;
        }
    
        // Joystick enabled is a global setting so first make sure there are any joysticks connected
        if (qgcApp()->toolbox()->joystickManager()->joysticks().count()) {
            _joystickEnabled = settings.value(_joystickEnabledSettingsKey, false).toBool();
        }
    
    }
    
    void Vehicle::_saveSettings(void)
    {
        QSettings settings;
    
        settings.beginGroup(QString(_settingsGroup).arg(_id));
    
        settings.setValue(_joystickModeSettingsKey, _joystickMode);
    
        settings.setValue(_joystickEnabledSettingsKey, _joystickEnabled);
    
    }
    
    int Vehicle::joystickMode(void)
    {
        return _joystickMode;
    }
    
    void Vehicle::setJoystickMode(int mode)
    {
        if (mode < 0 || mode >= JoystickModeMax) {
            qCWarning(VehicleLog) << "Invalid joystick mode" << mode;
            return;
        }
    
        _joystickMode = (JoystickMode_t)mode;
        _saveSettings();
        emit joystickModeChanged(mode);
    }
    
    QStringList Vehicle::joystickModes(void)
    {
        QStringList list;
    
        list << "Normal" << "Attitude" << "Position" << "Force" << "Velocity";
    
    
    bool Vehicle::joystickEnabled(void)
    {
        return _joystickEnabled;
    }
    
    void Vehicle::setJoystickEnabled(bool enabled)
    {
    
        _startJoystick(_joystickEnabled);
        _saveSettings();
    
        emit joystickEnabledChanged(_joystickEnabled);
    
    }
    
    void Vehicle::_startJoystick(bool start)
    {
    
        Joystick* joystick = _joystickManager->activeJoystick();
    
        if (joystick) {
            if (start) {
                if (_joystickEnabled) {
                    joystick->startPolling(this);
                }
            } else {
                joystick->stopPolling();
            }
        }
    }
    
    bool Vehicle::active(void)
    {
        return _active;
    }
    
    void Vehicle::setActive(bool active)
    {
        _active = active;
    
        _startJoystick(_active);
    }
    
    bool Vehicle::homePositionAvailable(void)
    {
        return _homePositionAvailable;
    }
    
    QGeoCoordinate Vehicle::homePosition(void)
    {
        return _homePosition;
    }
    
    Don Gagne's avatar
    Don Gagne committed
    
    void Vehicle::setArmed(bool armed)
    {
        // We specifically use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM since it is supported by more flight stacks.
    
    Don Gagne's avatar
    Don Gagne committed
        mavlink_message_t msg;
        mavlink_command_long_t cmd;
    
    Don Gagne's avatar
    Don Gagne committed
        cmd.command = (uint16_t)MAV_CMD_COMPONENT_ARM_DISARM;
        cmd.confirmation = 0;
        cmd.param1 = armed ? 1.0f : 0.0f;
        cmd.param2 = 0.0f;
        cmd.param3 = 0.0f;
        cmd.param4 = 0.0f;
        cmd.param5 = 0.0f;
        cmd.param6 = 0.0f;
        cmd.param7 = 0.0f;
        cmd.target_system = id();
    
        cmd.target_component = defaultComponentId();
    
    Don Gagne's avatar
    Don Gagne committed
        mavlink_msg_command_long_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &cmd);
    
        sendMessageOnPriorityLink(msg);
    
    Don Gagne's avatar
    Don Gagne committed
    }
    
    bool Vehicle::flightModeSetAvailable(void)
    {
        return _firmwarePlugin->isCapable(FirmwarePlugin::SetFlightModeCapability);
    }
    
    QStringList Vehicle::flightModes(void)
    {
    
    Daniel Agar's avatar
    Daniel Agar committed
        return _firmwarePlugin->flightModes(this);
    
    Don Gagne's avatar
    Don Gagne committed
    QString Vehicle::flightMode(void) const
    
    Don Gagne's avatar
    Don Gagne committed
    {
        return _firmwarePlugin->flightMode(_base_mode, _custom_mode);
    }
    
    void Vehicle::setFlightMode(const QString& flightMode)
    {
        uint8_t     base_mode;
        uint32_t    custom_mode;
    
        if (_firmwarePlugin->setFlightMode(flightMode, &base_mode, &custom_mode)) {
            // setFlightMode will only set MAV_MODE_FLAG_CUSTOM_MODE_ENABLED in base_mode, we need to move back in the existing
            // states.
            uint8_t newBaseMode = _base_mode & ~MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE;
            newBaseMode |= base_mode;
    
            mavlink_message_t msg;
            mavlink_msg_set_mode_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, id(), newBaseMode, custom_mode);
    
            sendMessageOnPriorityLink(msg);
    
    Don Gagne's avatar
    Don Gagne committed
        } else {
    
    Don Gagne's avatar
    Don Gagne committed
            qWarning() << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode;
    
    Don Gagne's avatar
    Don Gagne committed
        }
    }
    
    bool Vehicle::hilMode(void)
    {
        return _base_mode & MAV_MODE_FLAG_HIL_ENABLED;
    }
    
    void Vehicle::setHilMode(bool hilMode)
    {
        mavlink_message_t msg;
    
        uint8_t newBaseMode = _base_mode & ~MAV_MODE_FLAG_DECODE_POSITION_HIL;
        if (hilMode) {
            newBaseMode |= MAV_MODE_FLAG_HIL_ENABLED;
        }
    
        mavlink_msg_set_mode_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, id(), newBaseMode, _custom_mode);
    
        sendMessageOnPriorityLink(msg);
    
    
    bool Vehicle::missingParameters(void)
    {
        return _autopilotPlugin->missingParameters();
    }
    
    void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple)
    
    {
        mavlink_message_t               msg;
        mavlink_request_data_stream_t   dataStream;
    
        dataStream.req_stream_id = stream;
        dataStream.req_message_rate = rate;
        dataStream.start_stop = 1;  // start
        dataStream.target_system = id();
    
        dataStream.target_component = defaultComponentId();
    
        mavlink_msg_request_data_stream_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &dataStream);
    
    
        if (sendMultiple) {
            // We use sendMessageMultiple since we really want these to make it to the vehicle
            sendMessageMultiple(msg);
        } else {
    
            sendMessageOnPriorityLink(msg);
    
    }
    
    void Vehicle::_sendMessageMultipleNext(void)
    {
        if (_nextSendMessageMultipleIndex < _sendMessageMultipleList.count()) {
            qCDebug(VehicleLog) << "_sendMessageMultipleNext:" << _sendMessageMultipleList[_nextSendMessageMultipleIndex].message.msgid;
    
            sendMessageOnPriorityLink(_sendMessageMultipleList[_nextSendMessageMultipleIndex].message);
    
            if (--_sendMessageMultipleList[_nextSendMessageMultipleIndex].retryCount <= 0) {
                _sendMessageMultipleList.removeAt(_nextSendMessageMultipleIndex);
            } else {
                _nextSendMessageMultipleIndex++;
            }
        }
    
        if (_nextSendMessageMultipleIndex >= _sendMessageMultipleList.count()) {
            _nextSendMessageMultipleIndex = 0;
        }
    }
    
    void Vehicle::sendMessageMultiple(mavlink_message_t message)
    {
        SendMessageMultipleInfo_t   info;
    
        info.message =      message;
        info.retryCount =   _sendMessageMultipleRetries;
    
        _sendMessageMultipleList.append(info);
    }
    
    
    void Vehicle::_missionManagerError(int errorCode, const QString& errorMsg)
    {
        Q_UNUSED(errorCode);
    
        qgcApp()->showMessage(QString("Error during Mission communication with Vehicle: %1").arg(errorMsg));
    
    
    void Vehicle::_addNewMapTrajectoryPoint(void)
    {
        if (_mapTrajectoryHaveFirstCoordinate) {
    
            // Keep three minutes of trajectory
            if (_mapTrajectoryList.count() * _mapTrajectoryMsecsBetweenPoints > 3 * 1000 * 60) {
                _mapTrajectoryList.removeAt(0)->deleteLater();
            }
    
            _mapTrajectoryList.append(new CoordinateVector(_mapTrajectoryLastCoordinate, _coordinate, this));
    
        }
        _mapTrajectoryHaveFirstCoordinate = true;
    
        _mapTrajectoryLastCoordinate = _coordinate;
    
    }
    
    void Vehicle::_mapTrajectoryStart(void)
    {
        _mapTrajectoryHaveFirstCoordinate = false;
        _mapTrajectoryList.clear();
        _mapTrajectoryTimer.start();
    }
    
    void Vehicle::_mapTrajectoryStop()
    {
        _mapTrajectoryTimer.stop();
    }
    
    
    void Vehicle::_parametersReady(bool parametersReady)
    {
        if (parametersReady && !_missionManagerInitialRequestComplete) {
            _missionManagerInitialRequestComplete = true;
            _missionManager->requestMissionItems();
        }
    
    Lorenz Meier's avatar
    Lorenz Meier committed
    
        if (parametersReady) {
            setJoystickEnabled(_joystickEnabled);
        }
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::disconnectInactiveVehicle(void)
    
    Don Gagne's avatar
    Don Gagne committed
        // Vehicle is no longer communicating with us, disconnect all links
    
        LinkManager* linkMgr = qgcApp()->toolbox()->linkManager();
    
        for (int i=0; i<_links.count(); i++) {
    
            // FIXME: This linkInUse check is a hack fix for multiple vehicles on the same link.
            // The real fix requires significant restructuring which will come later.
            if (!qgcApp()->toolbox()->multiVehicleManager()->linkInUse(_links[i], this)) {
                linkMgr->disconnectLink(_links[i]);
            }
    
    
    ParameterLoader* Vehicle::getParameterLoader(void)
    {
        return _parameterLoader;
    }
    
    dogmaphobic's avatar
    dogmaphobic committed
    
    void Vehicle::_imageReady(UASInterface*)
    {
        if(_uas)
        {
            QImage img = _uas->getImage();
            qgcApp()->toolbox()->imageProvider()->setImage(&img, _id);
            _flowImageIndex++;
            emit flowImageIndexChanged();
        }
    }
    
    Don Gagne's avatar
    Don Gagne committed
    
    void Vehicle::_remoteControlRSSIChanged(uint8_t rssi)
    {
    
        if (_rcRSSIstore < 0 || _rcRSSIstore > 100) {
            _rcRSSIstore = rssi;
        }
    
    
    Don Gagne's avatar
    Don Gagne committed
        // Low pass to git rid of jitter
        _rcRSSIstore = (_rcRSSIstore * 0.9f) + ((float)rssi * 0.1);
        uint8_t filteredRSSI = (uint8_t)ceil(_rcRSSIstore);
        if(_rcRSSIstore < 0.1) {
            filteredRSSI = 0;
        }
        if(_rcRSSI != filteredRSSI) {
            _rcRSSI = filteredRSSI;
            emit rcRSSIChanged(_rcRSSI);
        }
    }
    
    Don Gagne's avatar
    Don Gagne committed
    
    void Vehicle::virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
    {
    
        // The following if statement prevents the virtualTabletJoystick from sending values if the standard joystick is enabled
        if ( !_joystickEnabled ) {
            _uas->setExternalControlSetpoint(roll, pitch, yaw, thrust, 0, JoystickModeRC);
        }
    
    
    void Vehicle::setConnectionLostEnabled(bool connectionLostEnabled)
    {
        if (_connectionLostEnabled != connectionLostEnabled) {
            _connectionLostEnabled = connectionLostEnabled;
            emit connectionLostEnabledChanged(_connectionLostEnabled);
        }
    }
    
    void Vehicle::_connectionLostTimeout(void)
    {
        if (_connectionLostEnabled && !_connectionLost) {
            _connectionLost = true;
    
            emit connectionLostChanged(true);
    
            _say(QString("%1 communication lost").arg(_vehicleIdSpeech()));
    
    Don Gagne's avatar
    Don Gagne committed
            if (_autoDisconnect) {
                disconnectInactiveVehicle();
            }
    
        }
    }
    
    void Vehicle::_connectionActive(void)
    {
        _connectionLostTimer.start();
        if (_connectionLost) {
            _connectionLost = false;
            emit connectionLostChanged(false);
    
    Don Gagne's avatar
    Don Gagne committed
            _say(QString("%1 communication regained").arg(_vehicleIdSpeech()));
    
    void Vehicle::_say(const QString& text)
    
        qgcApp()->toolbox()->audioOutput()->say(text.toLower());
    
    
    bool Vehicle::fixedWing(void) const
    {
        return vehicleType() == MAV_TYPE_FIXED_WING;
    }
    
    
    Don Gagne's avatar
    Don Gagne committed
    bool Vehicle::rover(void) const
    {
        return vehicleType() == MAV_TYPE_GROUND_ROVER;
    }
    
    
    bool Vehicle::multiRotor(void) const
    {
        switch (vehicleType()) {
        case MAV_TYPE_QUADROTOR:
        case MAV_TYPE_COAXIAL:
        case MAV_TYPE_HELICOPTER:
        case MAV_TYPE_HEXAROTOR:
        case MAV_TYPE_OCTOROTOR:
        case MAV_TYPE_TRICOPTER:
            return true;
        default:
            return false;
        }
    }
    
    Don Gagne's avatar
    Don Gagne committed
    bool Vehicle::vtol(void) const
    {
        switch (vehicleType()) {
        case MAV_TYPE_VTOL_DUOROTOR:
        case MAV_TYPE_VTOL_QUADROTOR:
        case MAV_TYPE_VTOL_TILTROTOR:
        case MAV_TYPE_VTOL_RESERVED2:
        case MAV_TYPE_VTOL_RESERVED3:
        case MAV_TYPE_VTOL_RESERVED4:
        case MAV_TYPE_VTOL_RESERVED5:
            return true;
        default:
            return false;
        }
    }
    
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::_setCoordinateValid(bool coordinateValid)
    {
        if (coordinateValid != _coordinateValid) {
            _coordinateValid = coordinateValid;
            emit coordinateValidChanged(_coordinateValid);
        }
    }
    
    
    QString Vehicle::vehicleTypeName() const {
        static QMap<int, QString> typeNames = {
            { MAV_TYPE_GENERIC,         tr("Generic micro air vehicle" )},
            { MAV_TYPE_FIXED_WING,      tr("Fixed wing aircraft")},
            { MAV_TYPE_QUADROTOR,       tr("Quadrotor")},
            { MAV_TYPE_COAXIAL,         tr("Coaxial helicopter")},
            { MAV_TYPE_HELICOPTER,      tr("Normal helicopter with tail rotor.")},
            { MAV_TYPE_ANTENNA_TRACKER, tr("Ground installation")},
            { MAV_TYPE_GCS,             tr("Operator control unit / ground control station")},
            { MAV_TYPE_AIRSHIP,         tr("Airship, controlled")},
            { MAV_TYPE_FREE_BALLOON,    tr("Free balloon, uncontrolled")},
            { MAV_TYPE_ROCKET,          tr("Rocket")},
            { MAV_TYPE_GROUND_ROVER,    tr("Ground rover")},
            { MAV_TYPE_SURFACE_BOAT,    tr("Surface vessel, boat, ship")},
            { MAV_TYPE_SUBMARINE,       tr("Submarine")},
            { MAV_TYPE_HEXAROTOR,       tr("Hexarotor")},
            { MAV_TYPE_OCTOROTOR,       tr("Octorotor")},
            { MAV_TYPE_TRICOPTER,       tr("Octorotor")},
            { MAV_TYPE_FLAPPING_WING,   tr("Flapping wing")},
            { MAV_TYPE_KITE,            tr("Flapping wing")},
            { MAV_TYPE_ONBOARD_CONTROLLER, tr("Onboard companion controller")},
            { MAV_TYPE_VTOL_DUOROTOR,   tr("Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter")},
            { MAV_TYPE_VTOL_QUADROTOR,  tr("Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter")},
            { MAV_TYPE_VTOL_TILTROTOR,  tr("Tiltrotor VTOL")},
            { MAV_TYPE_VTOL_RESERVED2,  tr("VTOL reserved 2")},
            { MAV_TYPE_VTOL_RESERVED3,  tr("VTOL reserved 3")},
            { MAV_TYPE_VTOL_RESERVED4,  tr("VTOL reserved 4")},
            { MAV_TYPE_VTOL_RESERVED5,  tr("VTOL reserved 5")},
            { MAV_TYPE_GIMBAL,          tr("Onboard gimbal")},
            { MAV_TYPE_ADSB,            tr("Onboard ADSB peripheral")},
        };
        return typeNames[_vehicleType];
    }
    
    
    /// Returns the string to speak to identify the vehicle
    QString Vehicle::_vehicleIdSpeech(void)
    {
        if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() > 1) {
            return QString("vehicle %1").arg(id());
        } else {
    
            return QString();
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::_handleFlightModeChanged(const QString& flightMode)
    
        _say(QString("%1 %2 flight mode").arg(_vehicleIdSpeech()).arg(flightMode));
    
    Don Gagne's avatar
    Don Gagne committed
        emit guidedModeChanged(_firmwarePlugin->isGuidedMode(this));
    
    }
    
    void Vehicle::_announceArmedChanged(bool armed)
    {
        _say(QString("%1 %2").arg(_vehicleIdSpeech()).arg(armed ? QStringLiteral("armed") : QStringLiteral("disarmed")));
    
    void Vehicle::clearTrajectoryPoints(void)
    {
        _mapTrajectoryList.clearAndDeleteContents();
    }
    
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::setFlying(bool flying)
    {
        if (armed() && _flying != flying) {
            _flying = flying;
            emit flyingChanged(flying);
        }
    }
    
    bool Vehicle::guidedModeSupported(void) const
    {
        return _firmwarePlugin->isCapable(FirmwarePlugin::GuidedModeCapability);
    }
    
    bool Vehicle::pauseVehicleSupported(void) const
    {
        return _firmwarePlugin->isCapable(FirmwarePlugin::PauseVehicleCapability);
    }
    
    void Vehicle::guidedModeRTL(void)
    {
        if (!guidedModeSupported()) {
    
            qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
    
    Don Gagne's avatar
    Don Gagne committed
            return;
        }
        _firmwarePlugin->guidedModeRTL(this);
    }
    
    void Vehicle::guidedModeLand(void)
    {
        if (!guidedModeSupported()) {
    
            qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
    
    Don Gagne's avatar
    Don Gagne committed
            return;
        }
        _firmwarePlugin->guidedModeLand(this);
    }
    
    void Vehicle::guidedModeTakeoff(double altitudeRel)
    {
        if (!guidedModeSupported()) {
    
            qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
    
    Don Gagne's avatar
    Don Gagne committed
            return;
        }
        setGuidedMode(true);
        _firmwarePlugin->guidedModeTakeoff(this, altitudeRel);
    }
    
    void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord)
    {
        if (!guidedModeSupported()) {
    
            qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
    
    Don Gagne's avatar
    Don Gagne committed
            return;
        }
        _firmwarePlugin->guidedModeGotoLocation(this, gotoCoord);
    }
    
    void Vehicle::guidedModeChangeAltitude(double altitudeRel)
    {
        if (!guidedModeSupported()) {
    
            qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
    
    Don Gagne's avatar
    Don Gagne committed
            return;
        }
        _firmwarePlugin->guidedModeChangeAltitude(this, altitudeRel);
    }
    
    void Vehicle::pauseVehicle(void)
    {
        if (!pauseVehicleSupported()) {
            qgcApp()->showMessage(QStringLiteral("Pause not supported by vehicle."));
            return;
        }
        _firmwarePlugin->pauseVehicle(this);
    }
    
    bool Vehicle::guidedMode(void) const
    {
        return _firmwarePlugin->isGuidedMode(this);
    }
    
    void Vehicle::setGuidedMode(bool guidedMode)
    {
        return _firmwarePlugin->setGuidedMode(this, guidedMode);
    }
    
    void Vehicle::emergencyStop(void)
    {
        mavlink_message_t msg;
        mavlink_command_long_t cmd;
    
        cmd.command = (uint16_t)MAV_CMD_COMPONENT_ARM_DISARM;
        cmd.confirmation = 0;
        cmd.param1 = 0.0f;
        cmd.param2 = 21196.0f;  // Magic number for emergency stop
        cmd.param3 = 0.0f;
        cmd.param4 = 0.0f;
        cmd.param5 = 0.0f;
        cmd.param6 = 0.0f;
        cmd.param7 = 0.0f;
        cmd.target_system = id();
    
        cmd.target_component = defaultComponentId();
    
    Don Gagne's avatar
    Don Gagne committed
        mavlink_msg_command_long_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &cmd);
    
    
        sendMessageOnPriorityLink(msg);
    
    void Vehicle::setCurrentMissionSequence(int seq)
    {
        if (!_firmwarePlugin->sendHomePositionToVehicle()) {
            seq--;
        }
        mavlink_message_t msg;
        mavlink_msg_mission_set_current_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, id(), _compID, seq);
    
        sendMessageOnPriorityLink(msg);
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::doCommandLong(int component, MAV_CMD command, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
    {
        mavlink_message_t       msg;
        mavlink_command_long_t  cmd;
    
        cmd.command = command;
        cmd.confirmation = 0;
        cmd.param1 = param1;
        cmd.param2 = param2;
        cmd.param3 = param3;
        cmd.param4 = param4;
        cmd.param5 = param5;
        cmd.param6 = param6;
        cmd.param7 = param7;
        cmd.target_system = id();
        cmd.target_component = component;
        mavlink_msg_command_long_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &cmd);
    
    
        sendMessageOnPriorityLink(msg);
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::setPrearmError(const QString& prearmError)
    {
        _prearmError = prearmError;
        emit prearmErrorChanged(_prearmError);
        if (!_prearmError.isEmpty()) {
            _prearmErrorTimer.start();
        }
    }
    
    void Vehicle::_prearmErrorTimeout(void)
    {
        setPrearmError(QString());
    }
    
    void Vehicle::setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType)
    
    Don Gagne's avatar
    Don Gagne committed
    {
        _firmwareMajorVersion = majorVersion;
        _firmwareMinorVersion = minorVersion;
        _firmwarePatchVersion = patchVersion;
    
        _firmwareVersionType = versionType;
        emit firmwareMajorVersionChanged(_firmwareMajorVersion);
        emit firmwareMinorVersionChanged(_firmwareMinorVersion);
        emit firmwarePatchVersionChanged(_firmwarePatchVersion);
        emit firmwareVersionTypeChanged(_firmwareVersionType);
    }
    
    QString Vehicle::firmwareVersionTypeString(void) const
    {
        switch (_firmwareVersionType) {
        case FIRMWARE_VERSION_TYPE_DEV:
            return QStringLiteral("dev");
        case FIRMWARE_VERSION_TYPE_ALPHA:
            return QStringLiteral("alpha");
        case FIRMWARE_VERSION_TYPE_BETA:
            return QStringLiteral("beta");
        case FIRMWARE_VERSION_TYPE_RC:
            return QStringLiteral("rc");
        case FIRMWARE_VERSION_TYPE_OFFICIAL:
        default:
            return QStringLiteral("");
        }
    
    void Vehicle::rebootVehicle()
    {
    
        doCommandLong(defaultComponentId(), MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f);
    
    Don Gagne's avatar
    Don Gagne committed
    int Vehicle::defaultComponentId(void)
    {
        return _parameterLoader->defaultComponenentId();
    }
    
    
    void Vehicle::setSoloFirmware(bool soloFirmware)
    {
        if (soloFirmware != _soloFirmware) {
            _soloFirmware = soloFirmware;
            emit soloFirmwareChanged(soloFirmware);
        }
    }
    
    
    const char* VehicleGPSFactGroup::_hdopFactName =                "hdop";
    const char* VehicleGPSFactGroup::_vdopFactName =                "vdop";
    const char* VehicleGPSFactGroup::_courseOverGroundFactName =    "courseOverGround";
    const char* VehicleGPSFactGroup::_countFactName =               "count";
    const char* VehicleGPSFactGroup::_lockFactName =                "lock";
    
    Don Gagne's avatar
    Don Gagne committed
    
    VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
        : FactGroup(1000, ":/json/Vehicle/GPSFact.json", parent)
        , _vehicle(NULL)
        , _hdopFact             (0, _hdopFactName,              FactMetaData::valueTypeDouble)
        , _vdopFact             (0, _vdopFactName,              FactMetaData::valueTypeDouble)
        , _courseOverGroundFact (0, _courseOverGroundFactName,  FactMetaData::valueTypeDouble)
        , _countFact            (0, _countFactName,             FactMetaData::valueTypeInt32)
        , _lockFact             (0, _lockFactName,              FactMetaData::valueTypeInt32)
    {
        _addFact(&_hdopFact,                _hdopFactName);
        _addFact(&_vdopFact,                _vdopFactName);
        _addFact(&_courseOverGroundFact,    _courseOverGroundFactName);
        _addFact(&_lockFact,                _lockFactName);
        _addFact(&_countFact,               _countFactName);
    
    
        _hdopFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
        _vdopFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
        _courseOverGroundFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    
    Don Gagne's avatar
    Don Gagne committed
    }
    
    void VehicleGPSFactGroup::setVehicle(Vehicle* vehicle)
    {
        _vehicle = vehicle;
    
    
        if (!vehicle) {
            // Disconnected Vehicle
            return;
        }
    
    
    Don Gagne's avatar
    Don Gagne committed
        connect(_vehicle->uas(), &UASInterface::localizationChanged, this, &VehicleGPSFactGroup::_setSatLoc);
    
        UAS* pUas = dynamic_cast<UAS*>(_vehicle->uas());
        connect(pUas, &UAS::satelliteCountChanged,  this, &VehicleGPSFactGroup::_setSatelliteCount);
        connect(pUas, &UAS::satRawHDOPChanged,      this, &VehicleGPSFactGroup::_setSatRawHDOP);
        connect(pUas, &UAS::satRawVDOPChanged,      this, &VehicleGPSFactGroup::_setSatRawVDOP);
        connect(pUas, &UAS::satRawCOGChanged,       this, &VehicleGPSFactGroup::_setSatRawCOG);
    }
    
    void VehicleGPSFactGroup::_setSatelliteCount(double val, QString)
    {
        // I'm assuming that a negative value or over 99 means there is no GPS
        if(val < 0.0)  val = -1.0;
        if(val > 99.0) val = -1.0;
    
        _countFact.setRawValue(val);
    }
    
    void VehicleGPSFactGroup::_setSatRawHDOP(double val)
    {
        _hdopFact.setRawValue(val);
    }
    
    void VehicleGPSFactGroup::_setSatRawVDOP(double val)
    {
        _vdopFact.setRawValue(val);
    }
    
    void VehicleGPSFactGroup::_setSatRawCOG(double val)
    {
        _courseOverGroundFact.setRawValue(val);
    }
    
    void VehicleGPSFactGroup::_setSatLoc(UASInterface*, int fix)
    {
        _lockFact.setRawValue(fix);
    
        // fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D lock, 3: 3D lock
        if (fix > 2) {
            _vehicle->_setCoordinateValid(true);
        }
    }
    
    
    const char* VehicleBatteryFactGroup::_voltageFactName =                     "voltage";
    const char* VehicleBatteryFactGroup::_percentRemainingFactName =            "percentRemaining";
    const char* VehicleBatteryFactGroup::_percentRemainingAnnounceFactName =    "percentRemainingAnnounce";
    const char* VehicleBatteryFactGroup::_mahConsumedFactName =                 "mahConsumed";
    const char* VehicleBatteryFactGroup::_currentFactName =                     "current";
    const char* VehicleBatteryFactGroup::_temperatureFactName =                 "temperature";
    const char* VehicleBatteryFactGroup::_cellCountFactName =                   "cellCount";
    
    const char* VehicleBatteryFactGroup::_settingsGroup =                       "Vehicle.battery";
    const int   VehicleBatteryFactGroup::_percentRemainingAnnounceDefault =     30;
    
    const double VehicleBatteryFactGroup::_voltageUnavailable =           -1.0;
    const int    VehicleBatteryFactGroup::_percentRemainingUnavailable =  -1;
    const int    VehicleBatteryFactGroup::_mahConsumedUnavailable =       -1;
    const int    VehicleBatteryFactGroup::_currentUnavailable =           -1;
    const double VehicleBatteryFactGroup::_temperatureUnavailable =       -1.0;
    const int    VehicleBatteryFactGroup::_cellCountUnavailable =         -1.0;
    
    
    SettingsFact* VehicleBatteryFactGroup::_percentRemainingAnnounceFact = NULL;
    
    Don Gagne's avatar
    Don Gagne committed
    VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
        : FactGroup(1000, ":/json/Vehicle/BatteryFact.json", parent)
        , _vehicle(NULL)
    
        , _voltageFact                  (0, _voltageFactName,                   FactMetaData::valueTypeDouble)
        , _percentRemainingFact         (0, _percentRemainingFactName,          FactMetaData::valueTypeInt32)
        , _mahConsumedFact              (0, _mahConsumedFactName,               FactMetaData::valueTypeInt32)
        , _currentFact                  (0, _currentFactName,                   FactMetaData::valueTypeInt32)
        , _temperatureFact              (0, _temperatureFactName,               FactMetaData::valueTypeDouble)
        , _cellCountFact                (0, _cellCountFactName,                 FactMetaData::valueTypeInt32)
    {
    
        _addFact(&_voltageFact,                 _voltageFactName);
        _addFact(&_percentRemainingFact,        _percentRemainingFactName);
        _addFact(percentRemainingAnnounce(),    _percentRemainingAnnounceFactName);
        _addFact(&_mahConsumedFact,             _mahConsumedFactName);
        _addFact(&_currentFact,                 _currentFactName);
        _addFact(&_temperatureFact,             _temperatureFactName);
        _addFact(&_cellCountFact,               _cellCountFactName);
    
    Don Gagne's avatar
    Don Gagne committed
    
        // Start out as not available
        _voltageFact.setRawValue            (_voltageUnavailable);
        _percentRemainingFact.setRawValue   (_percentRemainingUnavailable);
        _mahConsumedFact.setRawValue        (_mahConsumedUnavailable);
        _currentFact.setRawValue            (_currentUnavailable);
        _temperatureFact.setRawValue        (_temperatureUnavailable);
        _cellCountFact.setRawValue          (_cellCountUnavailable);
    }
    
    void VehicleBatteryFactGroup::setVehicle(Vehicle* vehicle)
    {
        _vehicle = vehicle;
    }
    
    Fact* VehicleBatteryFactGroup::percentRemainingAnnounce(void)
    {
        if (!_percentRemainingAnnounceFact) {
            _percentRemainingAnnounceFact = new SettingsFact(_settingsGroup, _percentRemainingAnnounceFactName, FactMetaData::valueTypeInt32, _percentRemainingAnnounceDefault);
        }
        return _percentRemainingAnnounceFact;
    }
    
    
    const char* VehicleWindFactGroup::_directionFactName =      "direction";
    const char* VehicleWindFactGroup::_speedFactName =          "speed";
    const char* VehicleWindFactGroup::_verticalSpeedFactName =  "verticalSpeed";
    
    
    Don Gagne's avatar
    Don Gagne committed
    VehicleWindFactGroup::VehicleWindFactGroup(QObject* parent)
        : FactGroup(1000, ":/json/Vehicle/WindFact.json", parent)
        , _vehicle(NULL)
        , _directionFact    (0, _directionFactName,     FactMetaData::valueTypeDouble)
        , _speedFact        (0, _speedFactName,         FactMetaData::valueTypeDouble)
        , _verticalSpeedFact(0, _verticalSpeedFactName, FactMetaData::valueTypeDouble)
    {
        _addFact(&_directionFact,       _directionFactName);
        _addFact(&_speedFact,           _speedFactName);
        _addFact(&_verticalSpeedFact,   _verticalSpeedFactName);
    
        // Start out as not available "--.--"
        _directionFact.setRawValue      (std::numeric_limits<float>::quiet_NaN());
        _speedFact.setRawValue          (std::numeric_limits<float>::quiet_NaN());
        _verticalSpeedFact.setRawValue  (std::numeric_limits<float>::quiet_NaN());
    }
    
    void VehicleWindFactGroup::setVehicle(Vehicle* vehicle)
    {
        _vehicle = vehicle;
    }
    
    const char* VehicleVibrationFactGroup::_xAxisFactName =      "xAxis";
    const char* VehicleVibrationFactGroup::_yAxisFactName =      "yAxis";
    const char* VehicleVibrationFactGroup::_zAxisFactName =      "zAxis";
    const char* VehicleVibrationFactGroup::_clipCount1FactName = "clipCount1";
    const char* VehicleVibrationFactGroup::_clipCount2FactName = "clipCount2";
    const char* VehicleVibrationFactGroup::_clipCount3FactName = "clipCount3";
    
    
    VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent)
        : FactGroup(1000, ":/json/Vehicle/VibrationFact.json", parent)
        , _vehicle(NULL)
        , _xAxisFact        (0, _xAxisFactName,         FactMetaData::valueTypeDouble)
        , _yAxisFact        (0, _yAxisFactName,         FactMetaData::valueTypeDouble)
        , _zAxisFact        (0, _zAxisFactName,         FactMetaData::valueTypeDouble)
        , _clipCount1Fact   (0, _clipCount1FactName,    FactMetaData::valueTypeUint32)
        , _clipCount2Fact   (0, _clipCount2FactName,    FactMetaData::valueTypeUint32)
        , _clipCount3Fact   (0, _clipCount3FactName,    FactMetaData::valueTypeUint32)
    {
        _addFact(&_xAxisFact,       _xAxisFactName);
        _addFact(&_yAxisFact,       _yAxisFactName);
        _addFact(&_zAxisFact,       _zAxisFactName);
        _addFact(&_clipCount1Fact,  _clipCount1FactName);
        _addFact(&_clipCount2Fact,  _clipCount2FactName);
        _addFact(&_clipCount3Fact,  _clipCount3FactName);
    
        // Start out as not available "--.--"
        _xAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
        _yAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
        _zAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    }
    
    void VehicleVibrationFactGroup::setVehicle(Vehicle* vehicle)
    {
        _vehicle = vehicle;
    }