Skip to content
Snippets Groups Projects
Vehicle.cc 182 KiB
Newer Older
  • Learn to ignore specific revisions
  • Don Gagne's avatar
     
    Don Gagne committed
        }
    
        // If the message is NOTIFY or higher severity, or starts with a '#',
        // then read it aloud.
    
        bool readAloud = false;
    
        if (messageText.startsWith("#")) {
    
            messageText.remove(0, 1);
    
            readAloud = true;
        }
        else if (severity <= MAV_SEVERITY_NOTICE) {
            readAloud = true;
        }
    
        if (readAloud) {
    
    Don Gagne's avatar
     
    Don Gagne committed
            if (!skipSpoken) {
                qgcApp()->toolbox()->audioOutput()->say(messageText);
            }
        }
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
        emit textMessageReceived(id(), compId, severity, messageText);
    }
    
    void Vehicle::_handleStatusText(mavlink_message_t& message)
    {
        QByteArray  b;
        QString     messageText;
    
        mavlink_statustext_t statustext;
        mavlink_msg_statustext_decode(&message, &statustext);
    
        uint8_t compId = message.compid;
    
        b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
        strncpy(b.data(), statustext.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
        b[b.length()-1] = '\0';
        messageText = QString(b);
        bool includesNullTerminator = messageText.length() < MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN;
    
        if (_chunkedStatusTextInfoMap.contains(compId) && _chunkedStatusTextInfoMap[compId].chunkId != statustext.id) {
            // We have an incomplete chunked status still pending
            _chunkedStatusTextInfoMap[compId].rgMessageChunks.append(QString());
            _chunkedStatusTextCompleted(compId);
        }
    
        if (statustext.id == 0) {
            // Non-chunked status text. We still use common chunked text output mechanism.
            ChunkedStatusTextInfo_t chunkedInfo;
            chunkedInfo.chunkId = 0;
            chunkedInfo.severity = statustext.severity;
            chunkedInfo.rgMessageChunks.append(messageText);
            _chunkedStatusTextInfoMap[compId] = chunkedInfo;
        } else {
            if (_chunkedStatusTextInfoMap.contains(compId)) {
                // A chunk sequence is in progress
                QStringList& chunks = _chunkedStatusTextInfoMap[compId].rgMessageChunks;
                if (statustext.chunk_seq > chunks.size()) {
                    // We are missing some chunks in between, fill them in as missing
                    for (int i=chunks.size(); i<statustext.chunk_seq; i++) {
                        chunks.append(QString());
                    }
                }
                chunks.append(messageText);
            } else {
                // Starting a new chunk sequence
                ChunkedStatusTextInfo_t chunkedInfo;
                chunkedInfo.chunkId = statustext.id;
                chunkedInfo.severity = statustext.severity;
                chunkedInfo.rgMessageChunks.append(messageText);
                _chunkedStatusTextInfoMap[compId] = chunkedInfo;
            }
            _chunkedStatusTextTimer.start();
        }
    
        if (statustext.id == 0 || includesNullTerminator) {
            _chunkedStatusTextTimer.stop();
            _chunkedStatusTextCompleted(message.compid);
        }
    
    Don Gagne's avatar
     
    Don Gagne committed
    }
    
    
    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(static_cast<int16_t>(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
        typedef enum ESTIMATOR_STATUS_FLAGS
        {
           ESTIMATOR_ATTITUDE=1, /* True if the attitude estimate is good | */
           ESTIMATOR_VELOCITY_HORIZ=2, /* True if the horizontal velocity estimate is good | */
           ESTIMATOR_VELOCITY_VERT=4, /* True if the  vertical velocity estimate is good | */
           ESTIMATOR_POS_HORIZ_REL=8, /* True if the horizontal position (relative) estimate is good | */
           ESTIMATOR_POS_HORIZ_ABS=16, /* True if the horizontal position (absolute) estimate is good | */
           ESTIMATOR_POS_VERT_ABS=32, /* True if the vertical position (absolute) estimate is good | */
           ESTIMATOR_POS_VERT_AGL=64, /* True if the vertical position (above ground) estimate is good | */
           ESTIMATOR_CONST_POS_MODE=128, /* True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) | */
           ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */
           ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */
           ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */
           ESTIMATOR_ACCEL_ERROR=2048, /* True if the EKF has detected bad accelerometer data | */
    
            typedef struct __mavlink_estimator_status_t {
             uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
             float vel_ratio; /*< Velocity innovation test ratio*/
             float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/
             float pos_vert_ratio; /*< Vertical position innovation test ratio*/
             float mag_ratio; /*< Magnetometer innovation test ratio*/
             float hagl_ratio; /*< Height above terrain innovation test ratio*/
             float tas_ratio; /*< True airspeed innovation test ratio*/
             float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/
             float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/
             uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/
    
            } mavlink_estimator_status_t;
        };
    
    void Vehicle::_handleDistanceSensor(mavlink_message_t& message)
    {
        mavlink_distance_sensor_t distanceSensor;
    
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
        mavlink_msg_distance_sensor_decode(&message, &distanceSensor);
    
    
        struct orientation2Fact_s {
            MAV_SENSOR_ORIENTATION  orientation;
            Fact*                   fact;
        };
    
        orientation2Fact_s rgOrientation2Fact[] =
        {
    
            { MAV_SENSOR_ROTATION_NONE,         _distanceSensorFactGroup.rotationNone() },
            { MAV_SENSOR_ROTATION_YAW_45,       _distanceSensorFactGroup.rotationYaw45() },
            { MAV_SENSOR_ROTATION_YAW_90,       _distanceSensorFactGroup.rotationYaw90() },
            { MAV_SENSOR_ROTATION_YAW_135,      _distanceSensorFactGroup.rotationYaw135() },
            { MAV_SENSOR_ROTATION_YAW_180,      _distanceSensorFactGroup.rotationYaw180() },
            { MAV_SENSOR_ROTATION_YAW_225,      _distanceSensorFactGroup.rotationYaw225() },
            { MAV_SENSOR_ROTATION_YAW_270,      _distanceSensorFactGroup.rotationYaw270() },
            { MAV_SENSOR_ROTATION_YAW_315,      _distanceSensorFactGroup.rotationYaw315() },
            { MAV_SENSOR_ROTATION_PITCH_90,     _distanceSensorFactGroup.rotationPitch90() },
            { MAV_SENSOR_ROTATION_PITCH_270,    _distanceSensorFactGroup.rotationPitch270() },
    
        };
    
        for (size_t i=0; i<sizeof(rgOrientation2Fact)/sizeof(rgOrientation2Fact[0]); i++) {
            const orientation2Fact_s& orientation2Fact = rgOrientation2Fact[i];
            if (orientation2Fact.orientation == distanceSensor.orientation) {
    
                orientation2Fact.fact->setRawValue(distanceSensor.current_distance / 100.0); // cm to meters
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    void Vehicle::_handleAttitudeTarget(mavlink_message_t& message)
    {
        mavlink_attitude_target_t attitudeTarget;
    
        mavlink_msg_attitude_target_decode(&message, &attitudeTarget);
    
        float roll, pitch, yaw;
        mavlink_quaternion_to_euler(attitudeTarget.q, &roll, &pitch, &yaw);
    
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        _setpointFactGroup.roll()->setRawValue(qRadiansToDegrees(roll));
        _setpointFactGroup.pitch()->setRawValue(qRadiansToDegrees(pitch));
        _setpointFactGroup.yaw()->setRawValue(qRadiansToDegrees(yaw));
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    
        _setpointFactGroup.rollRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_roll_rate));
        _setpointFactGroup.pitchRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_pitch_rate));
        _setpointFactGroup.yawRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_yaw_rate));
    }
    
    
    void Vehicle::_handleAttitudeWorker(double rollRadians, double pitchRadians, double yawRadians)
    
        double roll, pitch, yaw;
    
        roll = QGC::limitAngleToPMPIf(rollRadians);
        pitch = QGC::limitAngleToPMPIf(pitchRadians);
        yaw = QGC::limitAngleToPMPIf(yawRadians);
    
    
        roll = qRadiansToDegrees(roll);
        pitch = qRadiansToDegrees(pitch);
        yaw = qRadiansToDegrees(yaw);
    
        if (yaw < 0.0) {
            yaw += 360.0;
        }
        // truncate to integer so widget never displays 360
        yaw = trunc(yaw);
    
        _rollFact.setRawValue(roll);
        _pitchFact.setRawValue(pitch);
        _headingFact.setRawValue(yaw);
    
    }
    
    void Vehicle::_handleAttitude(mavlink_message_t& message)
    {
        if (_receivingAttitudeQuaternion) {
            return;
        }
    
        mavlink_attitude_t attitude;
        mavlink_msg_attitude_decode(&message, &attitude);
    
        _handleAttitudeWorker(attitude.roll, attitude.pitch, attitude.yaw);
    }
    
    void Vehicle::_handleAttitudeQuaternion(mavlink_message_t& message)
    {
        _receivingAttitudeQuaternion = true;
    
        mavlink_attitude_quaternion_t attitudeQuaternion;
        mavlink_msg_attitude_quaternion_decode(&message, &attitudeQuaternion);
    
    
        Eigen::Quaternionf quat(attitudeQuaternion.q1, attitudeQuaternion.q2, attitudeQuaternion.q3, attitudeQuaternion.q4);
        Eigen::Vector3f rates(attitudeQuaternion.rollspeed, attitudeQuaternion.pitchspeed, attitudeQuaternion.yawspeed);
        Eigen::Quaternionf repr_offset(attitudeQuaternion.repr_offset_q[0], attitudeQuaternion.repr_offset_q[1], attitudeQuaternion.repr_offset_q[2], attitudeQuaternion.repr_offset_q[3]);
    
        // if repr_offset is valid, rotate attitude and rates
        if (repr_offset.norm() >= 0.5f) {
            quat = quat * repr_offset;
    
            rates = repr_offset * rates;
    
        float q[] = { quat.w(), quat.x(), quat.y(), quat.z() };
    
        mavlink_quaternion_to_euler(q, &roll, &pitch, &yaw);
    
        _handleAttitudeWorker(roll, pitch, yaw);
    
        rollRate()->setRawValue(qRadiansToDegrees(rates[0]));
        pitchRate()->setRawValue(qRadiansToDegrees(rates[1]));
        yawRate()->setRawValue(qRadiansToDegrees(rates[2]));
    
    void Vehicle::_handleGpsRawInt(mavlink_message_t& message)
    {
        mavlink_gps_raw_int_t gpsRawInt;
        mavlink_msg_gps_raw_int_decode(&message, &gpsRawInt);
    
    
        _gpsRawIntMessageAvailable = true;
    
    
        if (gpsRawInt.fix_type >= GPS_FIX_TYPE_3D_FIX) {
    
            if (!_globalPositionIntMessageAvailable) {
    
                QGeoCoordinate newPosition(gpsRawInt.lat  / (double)1E7, gpsRawInt.lon / (double)1E7, gpsRawInt.alt  / 1000.0);
                if (newPosition != _coordinate) {
                    _coordinate = newPosition;
                    emit coordinateChanged(_coordinate);
                }
    
                _altitudeAMSLFact.setRawValue(gpsRawInt.alt / 1000.0);
    
        _gpsFactGroup.lat()->setRawValue(gpsRawInt.lat * 1e-7);
        _gpsFactGroup.lon()->setRawValue(gpsRawInt.lon * 1e-7);
    
        _gpsFactGroup.mgrs()->setRawValue(convertGeoToMGRS(QGeoCoordinate(gpsRawInt.lat * 1e-7, gpsRawInt.lon * 1e-7)));
    
        _gpsFactGroup.count()->setRawValue(gpsRawInt.satellites_visible == 255 ? 0 : gpsRawInt.satellites_visible);
    
        _gpsFactGroup.hdop()->setRawValue(gpsRawInt.eph == UINT16_MAX ? std::numeric_limits<double>::quiet_NaN() : gpsRawInt.eph / 100.0);
        _gpsFactGroup.vdop()->setRawValue(gpsRawInt.epv == UINT16_MAX ? std::numeric_limits<double>::quiet_NaN() : gpsRawInt.epv / 100.0);
        _gpsFactGroup.courseOverGround()->setRawValue(gpsRawInt.cog == UINT16_MAX ? std::numeric_limits<double>::quiet_NaN() : gpsRawInt.cog / 100.0);
    
        _gpsFactGroup.lock()->setRawValue(gpsRawInt.fix_type);
    }
    
    void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
    {
        mavlink_global_position_int_t globalPositionInt;
        mavlink_msg_global_position_int_decode(&message, &globalPositionInt);
    
    
        _altitudeRelativeFact.setRawValue(globalPositionInt.relative_alt / 1000.0);
        _altitudeAMSLFact.setRawValue(globalPositionInt.alt / 1000.0);
    
        // ArduPilot sends bogus GLOBAL_POSITION_INT messages with lat/lat 0/0 even when it has no gps signal
        // Apparently, this is in order to transport relative altitude information.
    
        if (globalPositionInt.lat == 0 && globalPositionInt.lon == 0) {
    
        _globalPositionIntMessageAvailable = true;
    
        QGeoCoordinate newPosition(globalPositionInt.lat  / (double)1E7, globalPositionInt.lon / (double)1E7, globalPositionInt.alt  / 1000.0);
        if (newPosition != _coordinate) {
            _coordinate = newPosition;
            emit coordinateChanged(_coordinate);
        }
    
    void Vehicle::_handleHighLatency2(mavlink_message_t& message)
    {
        mavlink_high_latency2_t highLatency2;
        mavlink_msg_high_latency2_decode(&message, &highLatency2);
    
    
        QString previousFlightMode;
        if (_base_mode != 0 || _custom_mode != 0){
            // Vehicle is initialized with _base_mode=0 and _custom_mode=0. Don't pass this to flightMode() since it will complain about
            // bad modes while unit testing.
            previousFlightMode = flightMode();
        }
        _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
        _custom_mode = _firmwarePlugin->highLatencyCustomModeTo32Bits(highLatency2.custom_mode);
        if (previousFlightMode != flightMode()) {
            emit flightModeChanged(flightMode());
        }
    
        // Assume armed since we don't know
        if (_armed != true) {
            _armed = true;
            emit armedChanged(_armed);
        }
    
    
        _coordinate.setLatitude(highLatency2.latitude  / (double)1E7);
        _coordinate.setLongitude(highLatency2.longitude / (double)1E7);
        _coordinate.setAltitude(highLatency2.altitude);
        emit coordinateChanged(_coordinate);
    
        _airSpeedFact.setRawValue((double)highLatency2.airspeed / 5.0);
        _groundSpeedFact.setRawValue((double)highLatency2.groundspeed / 5.0);
        _climbRateFact.setRawValue((double)highLatency2.climb_rate / 10.0);
        _headingFact.setRawValue((double)highLatency2.heading * 2.0);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        _altitudeRelativeFact.setRawValue(std::numeric_limits<double>::quiet_NaN());
        _altitudeAMSLFact.setRawValue(highLatency2.altitude);
    
    
        _windFactGroup.direction()->setRawValue((double)highLatency2.wind_heading * 2.0);
        _windFactGroup.speed()->setRawValue((double)highLatency2.windspeed / 5.0);
    
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        _battery1FactGroup.percentRemaining()->setRawValue(highLatency2.battery);
    
    
        _temperatureFactGroup.temperature1()->setRawValue(highLatency2.temperature_air);
    
        _gpsFactGroup.lat()->setRawValue(highLatency2.latitude * 1e-7);
        _gpsFactGroup.lon()->setRawValue(highLatency2.longitude * 1e-7);
    
        _gpsFactGroup.mgrs()->setRawValue(convertGeoToMGRS(QGeoCoordinate(highLatency2.latitude * 1e-7, highLatency2.longitude * 1e-7)));
    
        _gpsFactGroup.count()->setRawValue(0);
        _gpsFactGroup.hdop()->setRawValue(highLatency2.eph == UINT8_MAX ? std::numeric_limits<double>::quiet_NaN() : highLatency2.eph / 10.0);
        _gpsFactGroup.vdop()->setRawValue(highLatency2.epv == UINT8_MAX ? std::numeric_limits<double>::quiet_NaN() : highLatency2.epv / 10.0);
    
    
        struct failure2Sensor_s {
    
            HL_FAILURE_FLAG         failureBit;
    
            MAV_SYS_STATUS_SENSOR   sensorBit;
        };
    
        static const failure2Sensor_s rgFailure2Sensor[] = {
    
            { HL_FAILURE_FLAG_GPS,                      MAV_SYS_STATUS_SENSOR_GPS },
            { HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE,    MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE },
            { HL_FAILURE_FLAG_ABSOLUTE_PRESSURE,        MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE },
            { HL_FAILURE_FLAG_3D_ACCEL,                 MAV_SYS_STATUS_SENSOR_3D_ACCEL },
            { HL_FAILURE_FLAG_3D_GYRO,                  MAV_SYS_STATUS_SENSOR_3D_GYRO },
            { HL_FAILURE_FLAG_3D_MAG,                   MAV_SYS_STATUS_SENSOR_3D_MAG },
    
        };
    
        // Map from MAV_FAILURE bits to standard SYS_STATUS message handling
        uint32_t newOnboardControlSensorsEnabled = 0;
        for (size_t i=0; i<sizeof(rgFailure2Sensor)/sizeof(failure2Sensor_s); i++) {
            const failure2Sensor_s* pFailure2Sensor = &rgFailure2Sensor[i];
            if (highLatency2.failure_flags & pFailure2Sensor->failureBit) {
                // Assume if reporting as unhealthy that is it present and enabled
                newOnboardControlSensorsEnabled |= pFailure2Sensor->sensorBit;
            }
        }
        if (newOnboardControlSensorsEnabled != _onboardControlSensorsEnabled) {
            _onboardControlSensorsEnabled = newOnboardControlSensorsEnabled;
            _onboardControlSensorsPresent = newOnboardControlSensorsEnabled;
            _onboardControlSensorsUnhealthy = 0;
            emit unhealthySensorsChanged();
        }
    
    void Vehicle::_handleAltitude(mavlink_message_t& message)
    {
        mavlink_altitude_t altitude;
        mavlink_msg_altitude_decode(&message, &altitude);
    
    
        // If data from GPS is available it takes precedence over ALTITUDE message
        if (!_globalPositionIntMessageAvailable) {
            _altitudeRelativeFact.setRawValue(altitude.altitude_relative);
            if (!_gpsRawIntMessageAvailable) {
                _altitudeAMSLFact.setRawValue(altitude.altitude_amsl);
            }
        }
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    void Vehicle::_setCapabilities(uint64_t capabilityBits)
    {
    
        _capabilityBits = capabilityBits;
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
        _capabilityBitsKnown = true;
    
        emit capabilitiesKnownChanged(true);
    
        emit capabilityBitsChanged(_capabilityBits);
    
        QString supports("supports");
        QString doesNotSupport("does not support");
    
        qCDebug(VehicleLog) << QString("Vehicle %1 Mavlink 2.0").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ? supports : doesNotSupport);
        qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_ITEM_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_INT ? supports : doesNotSupport);
    
        qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_COMMAND_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_COMMAND_INT ? supports : doesNotSupport);
    
        qCDebug(VehicleLog) << QString("Vehicle %1 GeoFence").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE ? supports : doesNotSupport);
        qCDebug(VehicleLog) << QString("Vehicle %1 RallyPoints").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY ? supports : doesNotSupport);
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
        qCDebug(VehicleLog) << QString("Vehicle %1 Terrain").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_TERRAIN ? supports : doesNotSupport);
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
    
        _setMaxProtoVersionFromBothSources();
    
    Gus Grubba's avatar
    Gus Grubba committed
    void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& message)
    
        Q_UNUSED(link);
    
    
        mavlink_autopilot_version_t autopilotVersion;
        mavlink_msg_autopilot_version_decode(&message, &autopilotVersion);
    
    
    Gus Grubba's avatar
    Gus Grubba committed
        _uid = (quint64)autopilotVersion.uid;
        emit vehicleUIDChanged();
    
    
        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);
    
    Don Gagne's avatar
    Don Gagne committed
        if (px4Firmware()) {
            // Lower 3 bytes is custom version
            int majorVersion, minorVersion, patchVersion;
            majorVersion = autopilotVersion.flight_custom_version[2];
            minorVersion = autopilotVersion.flight_custom_version[1];
            patchVersion = autopilotVersion.flight_custom_version[0];
            setFirmwareCustomVersion(majorVersion, minorVersion, patchVersion);
    
    
            // PX4 Firmware stores the first 16 characters of the git hash as binary, with the individual bytes in reverse order
    
    Don Gagne's avatar
    Don Gagne committed
            _gitHash = "";
            for (int i = 7; i >= 0; i--) {
                _gitHash.append(QString("%1").arg(autopilotVersion.flight_custom_version[i], 2, 16, QChar('0')));
    
    Don Gagne's avatar
    Don Gagne committed
        } else {
            // APM Firmware stores the first 8 characters of the git hash as an ASCII character string
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
            char nullStr[9];
            strncpy(nullStr, (char*)autopilotVersion.flight_custom_version, 8);
            nullStr[8] = 0;
            _gitHash = nullStr;
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
        if (_toolbox->corePlugin()->options()->checkFirmwareVersion() && !_checkLatestStableFWDone) {
            _checkLatestStableFWDone = true;
    
    Don Gagne's avatar
     
    Don Gagne committed
            _firmwarePlugin->checkIfIsLatestStable(this);
        }
    
    Don Gagne's avatar
    Don Gagne committed
        emit gitHashChanged(_gitHash);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        _setCapabilities(autopilotVersion.capabilities);
        _startPlanRequest();
    
    void Vehicle::_handleProtocolVersion(LinkInterface *link, mavlink_message_t& message)
    {
        Q_UNUSED(link);
    
        mavlink_protocol_version_t protoVersion;
        mavlink_msg_protocol_version_decode(&message, &protoVersion);
    
    
    Don Gagne's avatar
     
    Don Gagne committed
        qCDebug(VehicleLog) << "_handleProtocolVersion" << protoVersion.max_version;
    
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
        _mavlinkProtocolRequestMaxProtoVersion = protoVersion.max_version;
    
    Don Gagne's avatar
     
    Don Gagne committed
        _mavlinkProtocolRequestComplete = true;
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
        _setMaxProtoVersionFromBothSources();
    
    Don Gagne's avatar
     
    Don Gagne committed
        _startPlanRequest();
    
    }
    
    void Vehicle::_setMaxProtoVersion(unsigned version) {
    
    
        // Set only once or if we need to reduce the max version
        if (_maxProtoVersion == 0 || version < _maxProtoVersion) {
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
            qCDebug(VehicleLog) << "_setMaxProtoVersion before:after" << _maxProtoVersion << version;
    
            _maxProtoVersion = version;
            emit requestProtocolVersion(_maxProtoVersion);
        }
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
    void Vehicle::_setMaxProtoVersionFromBothSources()
    {
        if (_mavlinkProtocolRequestComplete && _capabilityBitsKnown) {
            if (_mavlinkProtocolRequestMaxProtoVersion != 0) {
                qCDebug(VehicleLog) << "_setMaxProtoVersionFromBothSources using protocol version message";
                _setMaxProtoVersion(_mavlinkProtocolRequestMaxProtoVersion);
            } else {
                qCDebug(VehicleLog) << "_setMaxProtoVersionFromBothSources using capability bits";
                _setMaxProtoVersion(capabilityBits() & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ? 200 : 100);
            }
        }
    }
    
    
    Gus Grubba's avatar
    Gus Grubba committed
    QString Vehicle::vehicleUIDStr()
    {
        QString uid;
        uint8_t* pUid = (uint8_t*)(void*)&_uid;
        uid.sprintf("%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X",
    
                    pUid[0] & 0xff,
                pUid[1] & 0xff,
                pUid[2] & 0xff,
                pUid[3] & 0xff,
                pUid[4] & 0xff,
                pUid[5] & 0xff,
                pUid[6] & 0xff,
                pUid[7] & 0xff);
    
    Gus Grubba's avatar
    Gus Grubba committed
        return uid;
    }
    
    
    void Vehicle::_handleCommandLong(mavlink_message_t& message)
    {
    
    #ifdef NO_SERIAL_LINK
        // If not using serial link, bail out.
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        Q_UNUSED(message)
    #else
    
        mavlink_command_long_t cmd;
        mavlink_msg_command_long_decode(&message, &cmd);
    
        switch (cmd.command) {
    
        // Other component on the same system
        // requests that QGC frees up the serial port of the autopilot
        case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
            if (cmd.param6 > 0) {
                // disconnect the USB link if its a direct connection to a Pixhawk
                for (int i = 0; i < _links.length(); i++) {
                    SerialLink *sl = qobject_cast<SerialLink*>(_links.at(i));
                    if (sl && sl->getSerialConfig()->usbDirect()) {
                        qDebug() << "Disconnecting:" << _links.at(i)->getName();
                        qgcApp()->toolbox()->linkManager()->disconnectLink(_links.at(i));
    
                        emit linksChanged();
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    #endif
    
    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) {
        case MAV_LANDED_STATE_ON_GROUND:
    
            _setFlying(false);
            _setLanding(false);
    
    Don Gagne's avatar
    Don Gagne committed
            break;
    
        case MAV_LANDED_STATE_TAKEOFF:
    
    Don Gagne's avatar
    Don Gagne committed
        case MAV_LANDED_STATE_IN_AIR:
    
            _setFlying(true);
            _setLanding(false);
            break;
        case MAV_LANDED_STATE_LANDING:
            _setFlying(true);
            _setLanding(true);
            break;
        default:
            break;
    
    Don Gagne's avatar
    Don Gagne committed
        }
    
    
        if (vtol()) {
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
            bool vtolInFwdFlight = extendedState.vtol_state == MAV_VTOL_STATE_FW;
            if (vtolInFwdFlight != _vtolInFwdFlight) {
                _vtolInFwdFlight = vtolInFwdFlight;
                emit vtolInFwdFlightChanged(vtolInFwdFlight);
            }
    
    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));
    
    
    Don Gagne's avatar
     
    Don Gagne committed
        if (direction < 0) {
            direction += 360;
        }
    
    
        _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);
    
    
        // We don't want negative wind angles
        float direction = wind.direction;
        if (direction < 0) {
            direction += 360;
        }
        _windFactGroup.direction()->setRawValue(direction);
    
    Don Gagne's avatar
    Don Gagne committed
        _windFactGroup.speed()->setRawValue(wind.speed);
        _windFactGroup.verticalSpeed()->setRawValue(wind.speed_z);
    }
    
    bool Vehicle::_apmArmingNotRequired()
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    {
        QString armingRequireParam("ARMING_REQUIRE");
        return _parameterManager->parameterExists(FactSystem::defaultComponentId, armingRequireParam) &&
                _parameterManager->getParameter(FactSystem::defaultComponentId, armingRequireParam)->rawValue().toInt() == 0;
    }
    
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
    void Vehicle::_batteryStatusWorker(int batteryId, double voltage, double current, double batteryRemainingPct)
    {
        VehicleBatteryFactGroup* pBatteryFactGroup = nullptr;
        if (batteryId == 0) {
            pBatteryFactGroup = &_battery1FactGroup;
        } else if (batteryId == 1) {
            pBatteryFactGroup = &_battery2FactGroup;
        } else {
            return;
        }
    
        pBatteryFactGroup->voltage()->setRawValue(voltage);
        pBatteryFactGroup->current()->setRawValue(current);
        pBatteryFactGroup->instantPower()->setRawValue(voltage * current);
        pBatteryFactGroup->percentRemaining()->setRawValue(batteryRemainingPct);
    
        //-- Low battery warning
        if (batteryId == 0 && !qIsNaN(batteryRemainingPct)) {
            int warnThreshold = _settingsManager->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toInt();
            if (batteryRemainingPct < warnThreshold &&
                    batteryRemainingPct < _lastAnnouncedLowBatteryPercent &&
                    _lastBatteryAnnouncement.elapsed() > (batteryRemainingPct < warnThreshold * 0.5 ? 15000 : 30000)) {
                _say(tr("%1 low battery: %2 percent remaining").arg(_vehicleIdSpeech()).arg(static_cast<int>(batteryRemainingPct)));
                _lastBatteryAnnouncement.start();
                _lastAnnouncedLowBatteryPercent = static_cast<int>(batteryRemainingPct);
            }
        }
    }
    
    
    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 (_onboardControlSensorsPresent != sysStatus.onboard_control_sensors_present) {
            _onboardControlSensorsPresent = sysStatus.onboard_control_sensors_present;
            emit sensorsPresentBitsChanged(_onboardControlSensorsPresent);
        }
        if (_onboardControlSensorsEnabled != sysStatus.onboard_control_sensors_enabled) {
            _onboardControlSensorsEnabled = sysStatus.onboard_control_sensors_enabled;
            emit sensorsEnabledBitsChanged(_onboardControlSensorsEnabled);
        }
        if (_onboardControlSensorsHealth != sysStatus.onboard_control_sensors_health) {
            _onboardControlSensorsHealth = sysStatus.onboard_control_sensors_health;
            emit sensorsHealthBitsChanged(_onboardControlSensorsHealth);
        }
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        // ArduPilot firmare has a strange case when ARMING_REQUIRE=0. This means the vehicle is always armed but the motors are not
        // really powered up until the safety button is pressed. Because of this we can't depend on the heartbeat to tell us the true
        // armed (and dangerous) state. We must instead rely on SYS_STATUS telling us that the motors are enabled.
        if (apmFirmware() && _apmArmingNotRequired()) {
            _updateArmed(_onboardControlSensorsEnabled & MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS);
        }
    
    
        uint32_t newSensorsUnhealthy = _onboardControlSensorsEnabled & ~_onboardControlSensorsHealth;
        if (newSensorsUnhealthy != _onboardControlSensorsUnhealthy) {
            _onboardControlSensorsUnhealthy = newSensorsUnhealthy;
            emit unhealthySensorsChanged();
    
            emit sensorsUnhealthyBitsChanged(_onboardControlSensorsUnhealthy);
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
    
        // BATTERY_STATUS is currently unreliable on PX4 stack so we rely on SYS_STATUS for partial battery 0 information to work around it
        _batteryStatusWorker(0 /* batteryId */,
                             sysStatus.voltage_battery == UINT16_MAX ? qQNaN() : static_cast<double>(sysStatus.voltage_battery) / 1000.0,
                             sysStatus.current_battery == -1 ? qQNaN() : static_cast<double>(sysStatus.current_battery) / 100.0,
                             sysStatus.battery_remaining == -1 ? qQNaN() : sysStatus.battery_remaining);
    
    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);
    
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
        VehicleBatteryFactGroup* pBatteryFactGroup = nullptr;
        if (bat_status.id == 0) {
            pBatteryFactGroup = &_battery1FactGroup;
        } else if (bat_status.id == 1) {
            pBatteryFactGroup = &_battery2FactGroup;
    
    Don Gagne's avatar
    Don Gagne committed
        } else {
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
            return;
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
        double voltage = qQNaN();
    
    Don Gagne's avatar
    Don Gagne committed
        for (int i=0; i<10; i++) {
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
            double cellVoltage = bat_status.voltages[i] == UINT16_MAX ? qQNaN() : static_cast<double>(bat_status.voltages[i]) / 1000.0;
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
            if (qIsNaN(cellVoltage)) {
                break;
            }
            if (i == 0) {
                voltage = cellVoltage;
            } else {
                voltage += cellVoltage;
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
        pBatteryFactGroup->temperature()->setRawValue(bat_status.temperature == INT16_MAX ? qQNaN() : static_cast<double>(bat_status.temperature) / 100.0);
        pBatteryFactGroup->mahConsumed()->setRawValue(bat_status.current_consumed == -1  ? qQNaN() : bat_status.current_consumed);
        pBatteryFactGroup->chargeState()->setRawValue(bat_status.charge_state);
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
        pBatteryFactGroup->timeRemaining()->setRawValue(bat_status.time_remaining == 0 ? qQNaN() : bat_status.time_remaining);
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
    
    
    DoinLakeFlyer's avatar
     
    DoinLakeFlyer committed
        // BATTERY_STATUS is currently unreliable on PX4 stack so we rely on SYS_STATUS for partial battery 0 information to work around it
        if (bat_status.id != 0) {
            _batteryStatusWorker(bat_status.id,
                                 voltage,
                                 bat_status.current_battery == -1 ? qQNaN() : (double)bat_status.current_battery / 100.0,
                                 bat_status.battery_remaining == -1 ? qQNaN() : bat_status.battery_remaining);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    void Vehicle::_setHomePosition(QGeoCoordinate& homeCoord)
    {
        if (homeCoord != _homePosition) {
            _homePosition = homeCoord;
            emit homePositionChanged(_homePosition);
        }
    }
    
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::_handleHomePosition(mavlink_message_t& message)
    {
        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);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        _setHomePosition(newHomePosition);
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    void Vehicle::_updateArmed(bool armed)
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
        if (_armed != armed) {
            _armed = armed;
    
    Don Gagne's avatar
    Don Gagne committed
            emit armedChanged(_armed);
    
            // We are transitioning to the armed state, begin tracking trajectory points for the map
            if (_armed) {
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
                _trajectoryPoints->start();
                _flightTimerStart();
    
                _clearCameraTriggerPoints();
    
                // Reset battery warning
                _lastAnnouncedLowBatteryPercent = 100;
    
            } else {
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
                _trajectoryPoints->stop();
    
    DonLakeFlyer's avatar
     
    DonLakeFlyer committed
                _flightTimerStop();
    
                // Also handle Video Streaming
    
                if(qgcApp()->toolbox()->videoManager()->videoReceiver()) {
                    if(_settingsManager->videoSettings()->disableWhenDisarmed()->rawValue().toBool()) {
                        _settingsManager->videoSettings()->streamEnabled()->setRawValue(false);
                        qgcApp()->toolbox()->videoManager()->videoReceiver()->stop();
                    }
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    void Vehicle::_handlePing(LinkInterface* link, mavlink_message_t& message)
    {
        mavlink_ping_t      ping;
        mavlink_message_t   msg;
    
        mavlink_msg_ping_decode(&message, &ping);
    
        mavlink_msg_ping_pack_chan(static_cast<uint8_t>(_mavlink->getSystemId()),
                                   static_cast<uint8_t>(_mavlink->getComponentId()),
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
                                   priorityLink()->mavlinkChannel(),
                                   &msg,
                                   ping.time_usec,
                                   ping.seq,
                                   message.sysid,
                                   message.compid);
        sendMessageOnLink(link, msg);
    }
    
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    void Vehicle::_handleHeartbeat(mavlink_message_t& message)
    {
        if (message.compid != _defaultComponentId) {
            return;
        }
    
        mavlink_heartbeat_t heartbeat;
    
        mavlink_msg_heartbeat_decode(&message, &heartbeat);
    
        bool newArmed = heartbeat.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
    
        // ArduPilot firmare has a strange case when ARMING_REQUIRE=0. This means the vehicle is always armed but the motors are not
        // really powered up until the safety button is pressed. Because of this we can't depend on the heartbeat to tell us the true
        // armed (and dangerous) state. We must instead rely on SYS_STATUS telling us that the motors are enabled.
        if (apmFirmware()) {
            if (!_apmArmingNotRequired() || !(_onboardControlSensorsPresent & MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS)) {
                // If ARMING_REQUIRE!=0 or we haven't seen motor output status yet we use the hearbeat info for armed
                _updateArmed(newArmed);
            }
        } else {
            // Non-ArduPilot always updates from armed state in heartbeat
            _updateArmed(newArmed);
        }
    
    Don Gagne's avatar
    Don Gagne committed
    
        if (heartbeat.base_mode != _base_mode || heartbeat.custom_mode != _custom_mode) {
    
            QString previousFlightMode;
            if (_base_mode != 0 || _custom_mode != 0){
                // Vehicle is initialized with _base_mode=0 and _custom_mode=0. Don't pass this to flightMode() since it will complain about
                // bad modes while unit testing.
                previousFlightMode = flightMode();
            }
    
            _base_mode   = heartbeat.base_mode;
    
    Don Gagne's avatar
    Don Gagne committed
            _custom_mode = heartbeat.custom_mode;
    
            if (previousFlightMode != flightMode()) {
                emit flightModeChanged(flightMode());
            }
    
    void Vehicle::_handleRadioStatus(mavlink_message_t& message)
    {
    
        //-- Process telemetry status message
        mavlink_radio_status_t rstatus;
        mavlink_msg_radio_status_decode(&message, &rstatus);
    
        int rssi    = rstatus.rssi;
        int remrssi = rstatus.remrssi;
    
        int lnoise = (int)(int8_t)rstatus.noise;
        int rnoise = (int)(int8_t)rstatus.remnoise;
    
        //-- 3DR Si1k radio needs rssi fields to be converted to dBm
        if (message.sysid == '3' && message.compid == 'D') {
            /* Per the Si1K datasheet figure 23.25 and SI AN474 code
             * samples the relationship between the RSSI register
             * and received power is as follows:
             *
             *                       10
             * inputPower = rssi * ------ 127
             *                       19
             *
             * Additionally limit to the only realistic range [-120,0] dBm
             */
            rssi    = qMin(qMax(qRound(static_cast<qreal>(rssi)    / 1.9 - 127.0), - 120), 0);
            remrssi = qMin(qMax(qRound(static_cast<qreal>(remrssi) / 1.9 - 127.0), - 120), 0);
    
        } else {
            rssi    = (int)(int8_t)rstatus.rssi;
            remrssi = (int)(int8_t)rstatus.remrssi;
    
        }
        //-- Check for changes
        if(_telemetryLRSSI != rssi) {
            _telemetryLRSSI = rssi;
            emit telemetryLRSSIChanged(_telemetryLRSSI);
        }
        if(_telemetryRRSSI != remrssi) {
            _telemetryRRSSI = remrssi;
            emit telemetryRRSSIChanged(_telemetryRRSSI);
        }
        if(_telemetryRXErrors != rstatus.rxerrors) {
            _telemetryRXErrors = rstatus.rxerrors;
            emit telemetryRXErrorsChanged(_telemetryRXErrors);
        }
        if(_telemetryFixed != rstatus.fixed) {
            _telemetryFixed = rstatus.fixed;
            emit telemetryFixedChanged(_telemetryFixed);
        }
        if(_telemetryTXBuffer != rstatus.txbuf) {
            _telemetryTXBuffer = rstatus.txbuf;
            emit telemetryTXBufferChanged(_telemetryTXBuffer);
        }
    
        if(_telemetryLNoise != lnoise) {
            _telemetryLNoise = lnoise;
    
            emit telemetryLNoiseChanged(_telemetryLNoise);
        }
    
        if(_telemetryRNoise != rnoise) {
            _telemetryRNoise = rnoise;
    
            emit telemetryRNoiseChanged(_telemetryRNoise);
        }
    }
    
    
    // Ignore warnings from mavlink headers for both GCC/Clang and MSVC
    #ifdef __GNUC__
    
    #if __GNUC__ > 8
    #pragma GCC diagnostic push
    #pragma GCC diagnostic ignored "-Waddress-of-packed-member"
    #elif defined(__clang__)
    #pragma clang diagnostic push
    #pragma clang diagnostic ignored "-Waddress-of-packed-member"
    #else
    #pragma GCC diagnostic push
    #pragma GCC diagnostic ignored "-Wall"
    #endif
    
    #else
    #pragma warning(push, 0)
    #endif
    
    
    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;