Skip to content
Snippets Groups Projects
Vehicle.cc 37.7 KiB
Newer Older
  • Learn to ignore specific revisions
  •     emit joystickEnabledChanged(_joystickEnabled);
    
    }
    
    void Vehicle::_startJoystick(bool start)
    {
    
    #ifndef __mobile__
    
        Joystick* joystick = _joystickManager->activeJoystick();
    
        if (joystick) {
            if (start) {
                if (_joystickEnabled) {
                    joystick->startPolling(this);
                }
            } else {
                joystick->stopPolling();
            }
        }
    
    #else
        Q_UNUSED(start);
    #endif
    
    }
    
    bool Vehicle::active(void)
    {
        return _active;
    }
    
    void Vehicle::setActive(bool active)
    {
        _active = active;
    
        _startJoystick(_active);
    }
    
    
    QmlObjectListModel* Vehicle::missionItemsModel(void)
    {
    
        return missionManager()->missionItems();
    
    
    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 = 0;
    
    Don Gagne's avatar
    Don Gagne committed
        mavlink_msg_command_long_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &cmd);
    
    Don Gagne's avatar
    Don Gagne committed
        sendMessage(msg);
    }
    
    bool Vehicle::flightModeSetAvailable(void)
    {
        return _firmwarePlugin->isCapable(FirmwarePlugin::SetFlightModeCapability);
    }
    
    QStringList Vehicle::flightModes(void)
    {
        return _firmwarePlugin->flightModes();
    }
    
    QString Vehicle::flightMode(void)
    {
        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);
            sendMessage(msg);
        } 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);
        sendMessage(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 = 0;
    
        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 {
            sendMessage(msg);
        }
    
    }
    
    void Vehicle::_sendMessageMultipleNext(void)
    {
        if (_nextSendMessageMultipleIndex < _sendMessageMultipleList.count()) {
            qCDebug(VehicleLog) << "_sendMessageMultipleNext:" << _sendMessageMultipleList[_nextSendMessageMultipleIndex].message.msgid;
    
            sendMessage(_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) {
    
            _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++) {
    
    Don Gagne's avatar
    Don Gagne committed
            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)
    {
        // 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);
        }