Newer
Older
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);
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
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.*/
void Vehicle::_handleDistanceSensor(mavlink_message_t& message)
{
mavlink_distance_sensor_t 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
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);
_setpointFactGroup.roll()->setRawValue(qRadiansToDegrees(roll));
_setpointFactGroup.pitch()->setRawValue(qRadiansToDegrees(pitch));
_setpointFactGroup.yaw()->setRawValue(qRadiansToDegrees(yaw));
_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);
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
1157
1158
1159
1160
}
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 roll, pitch, yaw;
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);
_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);
_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);
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);
}
}
void Vehicle::_setCapabilities(uint64_t capabilityBits)
{
_capabilityBits = capabilityBits;
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);
qCDebug(VehicleLog) << QString("Vehicle %1 Terrain").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_TERRAIN ? supports : doesNotSupport);
void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& message)
mavlink_autopilot_version_t autopilotVersion;
mavlink_msg_autopilot_version_decode(&message, &autopilotVersion);
_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);
setFirmwareVersion(majorVersion, minorVersion, patchVersion, versionType);
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
_gitHash = "";
for (int i = 7; i >= 0; i--) {
_gitHash.append(QString("%1").arg(autopilotVersion.flight_custom_version[i], 2, 16, QChar('0')));
} else {
// APM Firmware stores the first 8 characters of the git hash as an ASCII character string
char nullStr[9];
strncpy(nullStr, (char*)autopilotVersion.flight_custom_version, 8);
nullStr[8] = 0;
_gitHash = nullStr;
if (_toolbox->corePlugin()->options()->checkFirmwareVersion() && !_checkLatestStableFWDone) {
_checkLatestStableFWDone = true;
_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);
qCDebug(VehicleLog) << "_handleProtocolVersion" << protoVersion.max_version;
}
void Vehicle::_setMaxProtoVersion(unsigned version) {
Lorenz Meier
committed
// Set only once or if we need to reduce the max version
if (_maxProtoVersion == 0 || version < _maxProtoVersion) {
qCDebug(VehicleLog) << "_setMaxProtoVersion before:after" << _maxProtoVersion << version;
Lorenz Meier
committed
_maxProtoVersion = version;
emit requestProtocolVersion(_maxProtoVersion);
}
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);
}
}
}
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);
Lorenz Meier
committed
void Vehicle::_handleCommandLong(mavlink_message_t& message)
{
#ifdef NO_SERIAL_LINK
// If not using serial link, bail out.
Lorenz Meier
committed
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));
Lorenz Meier
committed
}
}
Lorenz Meier
committed
break;
}
Lorenz Meier
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);
case MAV_LANDED_STATE_TAKEOFF:
_setFlying(true);
_setLanding(false);
break;
case MAV_LANDED_STATE_LANDING:
_setFlying(true);
_setLanding(true);
break;
default:
break;
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));
_windFactGroup.direction()->setRawValue(direction);
_windFactGroup.speed()->setRawValue(speed);
_windFactGroup.verticalSpeed()->setRawValue(0);
}
Gus Grubba
committed
#if !defined(NO_ARDUPILOT_DIALECT)
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);
_windFactGroup.speed()->setRawValue(wind.speed);
_windFactGroup.verticalSpeed()->setRawValue(wind.speed_z);
}
Gus Grubba
committed
#endif
bool Vehicle::_apmArmingNotRequired()
{
QString armingRequireParam("ARMING_REQUIRE");
return _parameterManager->parameterExists(FactSystem::defaultComponentId, armingRequireParam) &&
_parameterManager->getParameter(FactSystem::defaultComponentId, armingRequireParam)->rawValue().toInt() == 0;
}
1566
1567
1568
1569
1570
1571
1572
1573
1574
1575
1576
1577
1578
1579
1580
1581
1582
1583
1584
1585
1586
1587
1588
1589
1590
1591
1592
1593
1594
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);
}
}
}
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);
}
// 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);
// 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);
}
void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
{
mavlink_battery_status_t bat_status;
mavlink_msg_battery_status_decode(&message, &bat_status);
VehicleBatteryFactGroup* pBatteryFactGroup = nullptr;
if (bat_status.id == 0) {
pBatteryFactGroup = &_battery1FactGroup;
} else if (bat_status.id == 1) {
pBatteryFactGroup = &_battery2FactGroup;
double cellVoltage = bat_status.voltages[i] == UINT16_MAX ? qQNaN() : static_cast<double>(bat_status.voltages[i]) / 1000.0;
if (qIsNaN(cellVoltage)) {
break;
}
if (i == 0) {
voltage = cellVoltage;
} else {
voltage += cellVoltage;
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);
pBatteryFactGroup->timeRemaining()->setRawValue(bat_status.time_remaining == 0 ? qQNaN() : bat_status.time_remaining);
// 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);
void Vehicle::_setHomePosition(QGeoCoordinate& homeCoord)
{
if (homeCoord != _homePosition) {
_homePosition = homeCoord;
emit homePositionChanged(_homePosition);
}
}
void Vehicle::_handleHomePosition(mavlink_message_t& message)
{
mavlink_home_position_t homePos;
mavlink_msg_home_position_decode(&message, &homePos);
QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0,
homePos.longitude / 10000000.0,
homePos.altitude / 1000.0);
// We are transitioning to the armed state, begin tracking trajectory points for the map
if (_armed) {
_clearCameraTriggerPoints();
// Reset battery warning
_lastAnnouncedLowBatteryPercent = 100;
// 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();
}
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()),
priorityLink()->mavlinkChannel(),
&msg,
ping.time_usec,
ping.seq,
message.sysid,
message.compid);
sendMessageOnLink(link, msg);
}
1738
1739
1740
1741
1742
1743
1744
1745
1746
1747
1748
1749
1750
1751
1752
1753
1754
1755
1756
1757
1758
1759
1760
1761
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);
}
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();
}
if (previousFlightMode != flightMode()) {
emit flightModeChanged(flightMode());
}
void Vehicle::_handleRadioStatus(mavlink_message_t& message)
{
Lorenz Meier
committed
//-- Process telemetry status message
mavlink_radio_status_t rstatus;
mavlink_msg_radio_status_decode(&message, &rstatus);
Lorenz Meier
committed
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;
1806
1807
1808
1809
1810
1811
1812
1813
1814
1815
1816
1817
1818
1819
1820
1821
1822
1823
1824
1825
1826
1827
}
//-- 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);
}
}
1838
1839
1840
1841
1842
1843
1844
1845
1846
1847
1848
1849
1850
1851
1852
1853
1854
1855
1856
1857
1858
1859
1860
1861
1862
1863
1864
1865
1866
1867
1868
1869
1870
1871
1872
1873
1874
1875
1876
1877
1878
1879
1880
1881
1882
1883
1884
1885
1886
1887
1888
1889
1890
1891
1892
1893
1894
1895
1896
1897
1898
1899
1900
1901
1902
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;
for (int i=0; i<cMaxRcChannels; i++) {
pwmValues[i] = -1;
}
for (int i=0; i<8; i++) {
uint16_t channelValue = *_rgChannelvalues[i];
if (channelValue == UINT16_MAX) {
pwmValues[i] = -1;
} else {
pwmValues[i] = channelValue;
}
}
for (int i=9; i<18; i++) {
pwmValues[i] = -1;
}
emit remoteControlRSSIChanged(channels.rssi);
emit rcChannelsChanged(channelCount, pwmValues);
}
void Vehicle::_handleScaledPressure(mavlink_message_t& message) {
mavlink_scaled_pressure_t pressure;
mavlink_msg_scaled_pressure_decode(&message, &pressure);
_temperatureFactGroup.temperature1()->setRawValue(pressure.temperature / 100.0);
}
void Vehicle::_handleScaledPressure2(mavlink_message_t& message) {
mavlink_scaled_pressure2_t pressure;
mavlink_msg_scaled_pressure2_decode(&message, &pressure);
_temperatureFactGroup.temperature2()->setRawValue(pressure.temperature / 100.0);
}
void Vehicle::_handleScaledPressure3(mavlink_message_t& message) {
mavlink_scaled_pressure3_t pressure;
mavlink_msg_scaled_pressure3_decode(&message, &pressure);
_temperatureFactGroup.temperature3()->setRawValue(pressure.temperature / 100.0);
}
bool Vehicle::_containsLink(LinkInterface* link)
{
}
void Vehicle::_addLink(LinkInterface* link)
{
if (!_containsLink(link)) {
qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((qulonglong)link, 0, 16);
if (_links.count() <= 1) {
_updatePriorityLink(true /* updateActive */, false /* sendCommand */);
_updatePriorityLink(true /* updateActive */, true /* sendCommand */);
connect(_toolbox->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
connect(_toolbox->linkManager(), &LinkManager::linkDeleted, this, &Vehicle::_linkInactiveOrDeleted);
connect(link, &LinkInterface::highLatencyChanged, this, &Vehicle::_updateHighLatencyLink);
connect(link, &LinkInterface::activeChanged, this, &Vehicle::_linkActiveChanged);
void Vehicle::_linkInactiveOrDeleted(LinkInterface* link)
qCDebug(VehicleLog) << "_linkInactiveOrDeleted linkCount" << _links.count();
_updatePriorityLink(true /* updateActive */, true /* sendCommand */);
// Make sure to not send this more than one time
_allLinksInactiveSent = true;
emit allLinksInactive(this);
bool Vehicle::sendMessageOnLink(LinkInterface* link, mavlink_message_t message)
{
if (!link || !_links.contains(link) || !link->isConnected()) {
return false;
}
emit _sendMessageOnLinkOnThread(link, message);
return true;
}
void Vehicle::_sendMessageOnLink(LinkInterface* link, mavlink_message_t message)
{
// Make sure this is still a good link
if (!link || !_links.contains(link) || !link->isConnected()) {
return;
}