Newer
Older
_pitchFact.setRawValue(pitch);
_headingFact.setRawValue(yaw);
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
}
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);
float roll, pitch, yaw;
float q[] = { attitudeQuaternion.q1, attitudeQuaternion.q2, attitudeQuaternion.q3, attitudeQuaternion.q4 };
mavlink_quaternion_to_euler(q, &roll, &pitch, &yaw);
_handleAttitudeWorker(roll, pitch, yaw);
rollRate()->setRawValue(qRadiansToDegrees(attitudeQuaternion.rollspeed));
pitchRate()->setRawValue(qRadiansToDegrees(attitudeQuaternion.pitchspeed));
yawRate()->setRawValue(qRadiansToDegrees(attitudeQuaternion.yawspeed));
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.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.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);
Lorenz Meier
committed
// This should potentially be turned into a user-facing warning
// if the general experience after deployment is that users want MAVLink 2
// but forget to upgrade their radio firmware
if (capabilityBits & MAV_PROTOCOL_CAPABILITY_MAVLINK2 && maxProtoVersion() < 200) {
qCDebug(VehicleLog) << QString("Vehicle does support MAVLink 2 but the link does not allow for it.");
}
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);
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 = "";
QByteArray array((char*)autopilotVersion.flight_custom_version, 8);
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
_gitHash = QString::fromUtf8((char*)autopilotVersion.flight_custom_version, 8);
_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);
_setMaxProtoVersion(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);
// Now that the protocol version is known, the mission load is safe
// as it will use the right MAVLink version to enable all features
// the vehicle supports
_startPlanRequest();
Lorenz Meier
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);
void Vehicle::_handleHilActuatorControls(mavlink_message_t &message)
{
mavlink_hil_actuator_controls_t hil;
mavlink_msg_hil_actuator_controls_decode(&message, &hil);
emit hilActuatorControlsChanged(hil.time_usec, hil.flags,
hil.controls[0],
hil.controls[1],
hil.controls[2],
hil.controls[3],
hil.controls[4],
hil.controls[5],
hil.controls[6],
hil.controls[7],
hil.controls[8],
hil.controls[9],
hil.controls[10],
hil.controls[11],
hil.controls[12],
hil.controls[13],
hil.controls[14],
hil.controls[15],
hil.mode);
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(void)
{
QString armingRequireParam("ARMING_REQUIRE");
return _parameterManager->parameterExists(FactSystem::defaultComponentId, armingRequireParam) &&
_parameterManager->getParameter(FactSystem::defaultComponentId, armingRequireParam)->rawValue().toInt() == 0;
}
void Vehicle::_handleSysStatus(mavlink_message_t& message)
{
mavlink_sys_status_t sysStatus;
mavlink_msg_sys_status_decode(&message, &sysStatus);
if (sysStatus.current_battery == -1) {
_battery1FactGroup.current()->setRawValue(VehicleBatteryFactGroup::_currentUnavailable);
// Current is in Amps, current_battery is 10 * milliamperes (1 = 10 milliampere)
_battery1FactGroup.current()->setRawValue((float)sysStatus.current_battery / 100.0f);
}
if (sysStatus.voltage_battery == UINT16_MAX) {
_battery1FactGroup.voltage()->setRawValue(VehicleBatteryFactGroup::_voltageUnavailable);
_battery1FactGroup.voltage()->setRawValue((double)sysStatus.voltage_battery / 1000.0);
// current_battery is 10 mA and voltage_battery is 1mV. (10/1e3 times 1/1e3 = 1/1e5)
_battery1FactGroup.instantPower()->setRawValue((float)(sysStatus.current_battery*sysStatus.voltage_battery)/(100000.0));
_battery1FactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining);
if (sysStatus.battery_remaining > 0) {
if (sysStatus.battery_remaining < _settingsManager->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toInt() &&
sysStatus.battery_remaining < _lastAnnouncedLowBatteryPercent) {
_say(QString(tr("%1 low battery: %2 percent remaining")).arg(_vehicleIdSpeech()).arg(sysStatus.battery_remaining));
_lastAnnouncedLowBatteryPercent = sysStatus.battery_remaining;
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);
}
void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
{
mavlink_battery_status_t bat_status;
mavlink_msg_battery_status_decode(&message, &bat_status);
VehicleBatteryFactGroup& batteryFactGroup = bat_status.id == 0 ? _battery1FactGroup : _battery2FactGroup;
batteryFactGroup.temperature()->setRawValue(VehicleBatteryFactGroup::_temperatureUnavailable);
batteryFactGroup.temperature()->setRawValue((double)bat_status.temperature / 100.0);
batteryFactGroup.mahConsumed()->setRawValue(VehicleBatteryFactGroup::_mahConsumedUnavailable);
batteryFactGroup.mahConsumed()->setRawValue(bat_status.current_consumed);
}
int cellCount = 0;
for (int i=0; i<10; i++) {
if (bat_status.voltages[i] != UINT16_MAX) {
cellCount++;
}
}
if (cellCount == 0) {
cellCount = -1;
}
batteryFactGroup.cellCount()->setRawValue(cellCount);
//-- Time remaining in seconds (0 means not supported)
batteryFactGroup.timeRemaining()->setRawValue(bat_status.time_remaining);
//-- Battery charge state (0 means not supported)
if(bat_status.charge_state <= MAV_BATTERY_CHARGE_STATE_UNHEALTHY) {
batteryFactGroup.chargeState()->setRawValue(bat_status.charge_state);
}
//-- TODO: Somewhere, actions would be taken based on this chargeState:
// MAV_BATTERY_CHARGE_STATE_CRITICAL: Battery state is critical, return / abort immediately
// MAV_BATTERY_CHARGE_STATE_EMERGENCY: Battery state is too low for ordinary abortion, fastest possible emergency stop preventing damage
// MAV_BATTERY_CHARGE_STATE_FAILED: Battery failed, damage unavoidable
// MAV_BATTERY_CHARGE_STATE_UNHEALTHY: Battery is diagnosed to be broken or an error occurred, usage is discouraged / prohibited
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) {
_mapTrajectoryStart();
_clearCameraTriggerPoints();
// Also handle Video Streaming
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(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
ping.time_usec,
ping.seq,
message.sysid,
message.compid);
sendMessageOnLink(link, msg);
}
1585
1586
1587
1588
1589
1590
1591
1592
1593
1594
1595
1596
1597
1598
1599
1600
1601
1602
1603
1604
1605
1606
1607
1608
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();
}
_base_mode = heartbeat.base_mode;
_custom_mode = heartbeat.custom_mode;
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;
1653
1654
1655
1656
1657
1658
1659
1660
1661
1662
1663
1664
1665
1666
1667
1668
1669
1670
1671
1672
1673
1674
}
//-- 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);
}
}
1685
1686
1687
1688
1689
1690
1691
1692
1693
1694
1695
1696
1697
1698
1699
1700
1701
1702
1703
1704
1705
1706
1707
1708
1709
1710
1711
1712
1713
1714
1715
1716
1717
1718
1719
1720
1721
1722
1723
1724
1725
1726
1727
1728
1729
1730
1731
1732
1733
1734
1735
1736
1737
1738
1739
1740
1741
1742
1743
1744
1745
1746
1747
1748
1749
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((ulong)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();
if (_priorityLink.data() == link) {
_priorityLink.clear();
}
_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;
}
#if 0
// Leaving in for ease in Mav 2.0 testing
mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(link->mavlinkChannel());
qDebug() << "_sendMessageOnLink" << mavlinkStatus << link->mavlinkChannel() << mavlinkStatus->flags << message.magic;
#endif
// Give the plugin a chance to adjust
_firmwarePlugin->adjustOutgoingMavlinkMessage(this, link, &message);
// Write message into buffer, prepending start sign
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
int len = mavlink_msg_to_send_buffer(buffer, &message);
link->writeBytesSafe((const char*)buffer, len);
_messagesSent++;
emit messagesSentChanged();
void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand)
// if the priority link is commanded and still active don't change anything
if (_priorityLinkCommanded) {
if (_priorityLink.data()->link_active(_id)) {
return;
} else {
_priorityLinkCommanded = false;
}
}
LinkInterface* newPriorityLink = nullptr;
// This routine specifically does not clear _priorityLink when there are no links remaining.
// By doing this we hold a reference on the last link as the Vehicle shuts down. Thus preventing shutdown
// ordering nullptr pointer crashes where priorityLink() is still called during shutdown sequence.
if (_links.count() == 0) {
return;
}
// Check for the existing priority link to still be valid
for (int i=0; i<_links.count(); i++) {
if (_priorityLink.data() == _links[i]) {
if (!_priorityLink.data()->highLatency() && _priorityLink->link_active(_id)) {
// Link is still valid. Continue to use it unless it is high latency. In that case we still look for a better
// link to use as priority link.
return;
}
}
}
// The previous priority link is no longer valid. We must no find the best link available in this priority order:
// First active direct USB connection
// Any active non high latency link
// An active high latency link
// Any link
#ifndef NO_SERIAL_LINK
// Search for an active direct usb connection
for (int i=0; i<_links.count(); i++) {
LinkInterface* link = _links[i];
SerialLink* pSerialLink = qobject_cast<SerialLink*>(link);
if (pSerialLink) {
LinkConfiguration* config = pSerialLink->getLinkConfiguration();
if (config) {
SerialConfiguration* pSerialConfig = qobject_cast<SerialConfiguration*>(config);
if (pSerialConfig && pSerialConfig->usbDirect()) {
if (_priorityLink.data() != link && link->link_active(_id)) {
// Search for an active non-high latency link
for (int i=0; i<_links.count(); i++) {
LinkInterface* link = _links[i];
if (!link->highLatency() && link->link_active(_id)) {
newPriorityLink = link;
break;
}
}
}
if (!newPriorityLink) {
// Search for an active high latency link
for (int i=0; i<_links.count(); i++) {
LinkInterface* link = _links[i];
if (link->highLatency() && link->link_active(_id)) {
newPriorityLink = link;
break;
}
}
if (!newPriorityLink) {
// Use any link
newPriorityLink = _links[0];
if (_priorityLink.data() != newPriorityLink) {
if (_priorityLink) {
qgcApp()->showMessage((tr("switch to %2 as priority link")).arg(newPriorityLink->getName()));
}
_priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
_updateHighLatencyLink(sendCommand);
emit priorityLinkNameChanged(_priorityLink->getName());
if (updateActive) {
_linkActiveChanged(_priorityLink.data(), _priorityLink->link_active(_id), _id);
1970
1971
1972
1973
1974
1975
1976
1977
1978
1979
1980
1981
1982
1983
1984
1985
1986
1987
1988
1989
1990
1991
1992
1993
1994
1995
1996
1997
1998
1999
2000
int Vehicle::motorCount(void)
{
switch (_vehicleType) {
case MAV_TYPE_HELICOPTER:
return 1;
case MAV_TYPE_VTOL_DUOROTOR:
return 2;
case MAV_TYPE_TRICOPTER:
return 3;
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
return 4;
case MAV_TYPE_HEXAROTOR:
return 6;
case MAV_TYPE_OCTOROTOR:
return 8;
default:
return -1;
}
}
bool Vehicle::coaxialMotors(void)
{
return _firmwarePlugin->multiRotorCoaxialMotors(this);
}
bool Vehicle::xConfigMotors(void)
{
return _firmwarePlugin->multiRotorXConfig(this);
}