Newer
Older
/*===================================================================
======================================================================*/
/**
* @file
* @brief Represents one unmanned aerial vehicle
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QList>
#include <QMessageBox>
#include <QTimer>
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
#include "LinkManager.h"
#include "SerialLink.h"
#ifdef QGC_PROTOBUF_ENABLED
#include <google/protobuf/descriptor.h>
#endif
/**
* Gets the settings from the previous UAS (name, airframe, autopilot, battery specs)
* by calling readSettings. This means the new UAS will have the same settings
* as the previous one created unless one calls deleteSettings in the code after
* creating the UAS.
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id),
startTime(QGC::groundTimeMilliseconds()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(-1),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
waypointManager(this),
thrustSum(0),
thrustMax(10),
LM
committed
startVoltage(-1.0f),
tickVoltage(10.5f),
lastTickVoltageValue(13.0f),
tickLowpassVoltage(12.0f),
LM
committed
currentVoltage(12.6f),
lpVoltage(12.0f),
batteryRemainingEstimateEnabled(true),
mode(-1),
status(-1),
navMode(-1),
onboardTimeOffset(0),
controlRollManual(true),
controlPitchManual(true),
controlYawManual(true),
controlThrustManual(true),
manualRollAngle(0),
manualPitchAngle(0),
manualYawAngle(0),
manualThrust(0),
receiveDropRate(0),
sendDropRate(0),
lowBattAlarm(false),
positionLock(false),
localX(0.0),
localY(0.0),
localZ(0.0),
latitude(0.0),
longitude(0.0),
altitude(0.0),
roll(0.0),
pitch(0.0),
yaw(0.0),
statusTimeout(new QTimer(this)),
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
receivedOverlayTimestamp(0.0),
receivedObstacleListTimestamp(0.0),
receivedPathTimestamp(0.0),
receivedPointCloudTimestamp(0.0),
receivedRGBDImageTimestamp(0.0),
airframe(QGC_AIRFRAME_GENERIC),
attitudeKnown(false),
paramManager(NULL),
attitudeStamped(false),
lastAttitude(0),
Lorenz Meier
committed
simulation(new QGCXPlaneLink(this)),
isLocalPositionKnown(false),
isGlobalPositionKnown(false),
systemIsArmed(false),
nedPosGlobalOffset(0,0,0),
nedAttGlobalOffset(0,0,0),
connectionLost(false),
lastVoltageWarning(0),
lastNonNullTime(0),
onboardTimeOffsetInvalidCount(0)
for (unsigned int i = 0; i<255;++i)
{
componentID[i] = -1;
componentMulti[i] = false;
}
color = UASInterface::getNextColor();
connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
readSettings();
type = MAV_TYPE_GENERIC;
// Initial signals
emit disarmed();
/**
* Saves the settings of name, airframe, autopilot type and battery specifications
* by calling writeSettings.
*/
delete statusTimeout;
delete simulation;
}
* Saves the settings of name, airframe, autopilot type and battery specifications
* for the next instantiation of UAS.
void UAS::writeSettings()
{
QSettings settings;
settings.beginGroup(QString("MAV%1").arg(uasId));
settings.setValue("NAME", this->name);
settings.setValue("AIRFRAME", this->airframe);
settings.setValue("AP_TYPE", this->autopilot);
settings.setValue("BATTERY_SPECS", getBatterySpecs());
settings.endGroup();
settings.sync();
}
* Reads in the settings: name, airframe, autopilot type, and battery specifications
* for the new UAS.
*/
void UAS::readSettings()
{
QSettings settings;
settings.beginGroup(QString("MAV%1").arg(uasId));
this->name = settings.value("NAME", this->name).toString();
this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
setBatterySpecs(settings.value("BATTERY_SPECS").toString());
}
settings.endGroup();
}
* Deletes the settings origianally read into the UAS by readSettings.
* This is in case one does not want the old values but would rather
* start with the values assigned by the constructor.
*/
void UAS::deleteSettings()
{
this->name = "";
this->airframe = QGC_AIRFRAME_GENERIC;
this->autopilot = -1;
setBatterySpecs(QString("9V,9.5V,12.6V"));
}
int UAS::getUASID() const
void UAS::updateState()
{
// Check if heartbeat timed out
quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
if (!connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
connectionLost = true;
QString audiostring = QString("Link lost to system %1").arg(this->getUASID());
GAudioOutput::instance()->say(audiostring.toLower());
}
// Update connection loss time on each iteration
if (connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
{
connectionLossTime = heartbeatInterval;
Lorenz Meier
committed
emit heartbeatTimeout(true, heartbeatInterval/1000);
}
// Connection gained
if (connectionLost && (heartbeatInterval < timeoutIntervalHeartbeat))
{
QString audiostring = QString("Link regained to system %1 after %2 seconds").arg(this->getUASID()).arg((int)(connectionLossTime/1000000));
GAudioOutput::instance()->say(audiostring.toLower());
connectionLost = false;
connectionLossTime = 0;
Lorenz Meier
committed
emit heartbeatTimeout(false, 0);
// Position lock is set by the MAVLink message handler
// if no position lock is available, indicate an error
positionLock = false;
if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock)
GAudioOutput::instance()->notifyNegative();
}
}
}
* If the acitve UAS (the UAS that was selected) is not the one that is currently
* active, then change the active UAS to the one that was selected.
*/
if (UASManager::instance()->getActiveUAS() != this)
{
UASManager::instance()->setActiveUAS(this);
emit systemSelected(true);
}
}
* @return if the active UAS is the current UAS
bool UAS::getSelected() const
{
return (UASManager::instance()->getActiveUAS() == this);
}
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
if (!links->contains(link))
{
// qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
if (!components.contains(message.compid))
{
QString componentName;
switch (message.compid)
{
case MAV_COMP_ID_ALL:
{
componentName = "ANONYMOUS";
break;
}
{
componentName = "MISSIONPLANNER";
break;
}
}
components.insert(message.compid, componentName);
emit componentCreated(uasId, message.compid, componentName);
}
// qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;
// Only accept messages from this system (condition 1)
// and only then if a) attitudeStamped is disabled OR b) attitudeStamped is enabled
// and we already got one attitude packet
if (message.sysid == uasId && (!attitudeStamped || (attitudeStamped && (lastAttitude != 0)) || message.msgid == MAVLINK_MSG_ID_ATTITUDE))
{
bool multiComponentSourceDetected = false;
bool wrongComponent = false;
switch (message.compid)
{
case MAV_COMP_ID_IMU_2:
// Prefer IMU 2 over IMU 1 (FIXME)
componentID[message.msgid] = MAV_COMP_ID_IMU_2;
break;
default:
// Do nothing
break;
}
// Store component ID
if (componentID[message.msgid] == -1)
{
// Prefer the first component
componentID[message.msgid] = message.compid;
}
else
{
// Got this message already
if (componentID[message.msgid] != message.compid)
{
componentMulti[message.msgid] = true;
wrongComponent = true;
}
}
if (componentMulti[message.msgid] == true) multiComponentSourceDetected = true;
switch (message.msgid)
{
if (multiComponentSourceDetected && wrongComponent)
{
break;
}
mavlink_heartbeat_t state;
mavlink_msg_heartbeat_decode(&message, &state);
// Send the base_mode and system_status values to the plotter. This uses the ground time
// so the Ground Time checkbox must be ticked for these values to display
quint64 time = getUnixTime();
QString name = QString("M%1:HEARTBEAT.%2").arg(message.sysid);
emit valueChanged(uasId, name.arg("base_mode"), "bits", state.base_mode, time);
emit valueChanged(uasId, name.arg("custom_mode"), "bits", state.custom_mode, time);
emit valueChanged(uasId, name.arg("system_status"), "-", state.system_status, time);
{
if (airframe == 0)
{
switch (type)
{
setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
break;
setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
break;
case MAV_TYPE_HEXAROTOR:
setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
break;
default:
// Do nothing
break;
}
}
Mariano Lizarraga
committed
bool currentlyArmed = state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
if (systemIsArmed != currentlyArmed)
{
systemIsArmed = currentlyArmed;
emit armingChanged(systemIsArmed);
if (systemIsArmed)
{
emit armed();
}
else
{
emit disarmed();
}
}
LM
committed
QString audiostring = QString("System %1").arg(uasId);
QString stateAudio = "";
QString modeAudio = "";
QString navModeAudio = "";
bool statechanged = false;
bool modechanged = false;
LM
committed
QString audiomodeText = getAudioModeTextFor(static_cast<int>(state.base_mode));
LM
committed
if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT)
{
statechanged = true;
this->status = state.system_status;
getStatusForCode((int)state.system_status, uasState, stateDescription);
emit statusChanged(this, uasState, stateDescription);
emit statusChanged(this->status);
// Adjust for better audio
if (uasState == QString("STANDBY")) uasState = QString("standing by");
if (uasState == QString("EMERGENCY")) uasState = QString("emergency condition");
if (uasState == QString("CRITICAL")) uasState = QString("critical condition");
if (uasState == QString("SHUTDOWN")) uasState = QString("shutting down");
stateAudio = uasState;
if (this->mode != static_cast<int>(state.base_mode))
this->mode = static_cast<int>(state.base_mode);
shortModeText = getShortModeTextFor(this->mode);
Mariano Lizarraga
committed
emit modeChanged(this->getUASID(), shortModeText, "");
LM
committed
modeAudio = " is now in " + audiomodeText;
if (navMode != state.custom_mode)
emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
navMode = state.custom_mode;
//navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
Mariano Lizarraga
committed
// AUDIO
if (modechanged && statechanged)
{
// Output both messages
audiostring += modeAudio + " and " + stateAudio;
}
else if (modechanged || statechanged)
{
// Output the one message
audiostring += modeAudio + stateAudio + navModeAudio;
}
Mariano Lizarraga
committed
if (statechanged && ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY))
GAudioOutput::instance()->say(QString("emergency for system %1").arg(this->getUASID()));
QTimer::singleShot(3000, GAudioOutput::instance(), SLOT(startEmergency()));
}
else if (modechanged || statechanged)
{
GAudioOutput::instance()->stopEmergency();
GAudioOutput::instance()->say(audiostring.toLower());
break;
case MAVLINK_MSG_ID_SYS_STATUS:
{
if (multiComponentSourceDetected && wrongComponent)
{
break;
}
mavlink_sys_status_t state;
mavlink_msg_sys_status_decode(&message, &state);
Bryant Mairs
committed
// Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
quint64 time = getUnixTime();
QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid);
emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time);
emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time);
emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time);
emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time);
emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time);
emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time);
LM
committed
emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);
Bryant Mairs
committed
// Process CPU load.
Bryant Mairs
committed
emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
Bryant Mairs
committed
// Battery charge/time remaining/voltage calculations
currentVoltage = state.voltage_battery/1000.0f;
lpVoltage = filterVoltage(currentVoltage);
LM
committed
tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage;
LM
committed
// We don't want to tick above the threshold
if (tickLowpassVoltage > tickVoltage)
{
lastTickVoltageValue = tickLowpassVoltage;
}
if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f)
/* warn if lower than treshold */
&& (lpVoltage < tickVoltage)
/* warn only if we have at least the voltage of an empty LiPo cell, else we're sampling something wrong */
&& (currentVoltage > 3.3f)
/* warn only if current voltage is really still lower by a reasonable amount */
&& ((currentVoltage - 0.2f) < tickVoltage)
/* warn only every 12 seconds */
&& (QGC::groundTimeUsecs() - lastVoltageWarning) > 12000000)
LM
committed
{
GAudioOutput::instance()->say(QString("voltage warning: %1 volts").arg(lpVoltage, 0, 'f', 1, QChar(' ')));
lastVoltageWarning = QGC::groundTimeUsecs();
LM
committed
lastTickVoltageValue = tickLowpassVoltage;
}
if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage;
timeRemaining = calculateTimeRemaining();
if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
{
chargeLevel = state.battery_remaining;
}
emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
Bryant Mairs
committed
emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time);
emit voltageChanged(message.sysid, currentVoltage);
emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time);
// And if the battery current draw is measured, log that also.
if (state.current_battery != -1)
{
emit valueChanged(uasId, name.arg("battery_current"), "A", ((double)state.current_battery) / 100.0f, time);
}
Mariano Lizarraga
committed
if (lpVoltage < warnVoltage && (currentVoltage - 0.2f) < warnVoltage && (currentVoltage > 3.3))
Mariano Lizarraga
committed
// control_sensors_enabled:
// relevant bits: 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control
emit attitudeControlEnabled(state.onboard_control_sensors_enabled & (1 << 11));
emit positionYawControlEnabled(state.onboard_control_sensors_enabled & (1 << 12));
emit positionZControlEnabled(state.onboard_control_sensors_enabled & (1 << 13));
emit positionXYControlEnabled(state.onboard_control_sensors_enabled & (1 << 14));
// Trigger drop rate updates as needed. Here we convert the incoming
// drop_rate_comm value from 1/100 of a percent in a uint16 to a true
// percentage as a float. We also cap the incoming value at 100% as defined
// by the MAVLink specifications.
if (state.drop_rate_comm > 10000)
{
Bryant Mairs
committed
state.drop_rate_comm = 10000;
}
Bryant Mairs
committed
emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f);
emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time);
}
{
mavlink_attitude_t attitude;
mavlink_msg_attitude_decode(&message, &attitude);
quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time);
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
if (!wrongComponent)
{
lastAttitude = time;
roll = QGC::limitAngleToPMPIf(attitude.roll);
pitch = QGC::limitAngleToPMPIf(attitude.pitch);
yaw = QGC::limitAngleToPMPIf(attitude.yaw);
// // Emit in angles
// // Convert yaw angle to compass value
// // in 0 - 360 deg range
// float compass = (yaw/M_PI)*180.0+360.0f;
// if (compass > -10000 && compass < 10000)
// {
// while (compass > 360.0f) {
// compass -= 360.0f;
// }
// }
// else
// {
// // Set to 0, since it is an invalid value
// compass = 0.0f;
// }
attitudeKnown = true;
emit attitudeChanged(this, roll, pitch, yaw, time);
emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
}
case MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET:
{
mavlink_local_position_ned_system_global_offset_t offset;
mavlink_msg_local_position_ned_system_global_offset_decode(&message, &offset);
nedPosGlobalOffset.setX(offset.x);
nedPosGlobalOffset.setY(offset.y);
nedPosGlobalOffset.setZ(offset.z);
nedAttGlobalOffset.setX(offset.roll);
nedAttGlobalOffset.setY(offset.pitch);
nedAttGlobalOffset.setZ(offset.yaw);
}
break;
{
mavlink_hil_controls_t hil;
mavlink_msg_hil_controls_decode(&message, &hil);
emit hilControlsChanged(hil.time_usec, hil.roll_ailerons, hil.pitch_elevator, hil.yaw_rudder, hil.throttle, hil.mode, hil.nav_mode);
}
case MAVLINK_MSG_ID_VFR_HUD:
{
mavlink_vfr_hud_t hud;
mavlink_msg_vfr_hud_decode(&message, &hud);
quint64 time = getUnixTime();
// Display updated values
emit thrustChanged(this, hud.throttle/100.0);
if (!attitudeKnown)
{
yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
emit attitudeChanged(this, roll, pitch, yaw, time);
emit altitudeChanged(uasId, hud.alt);
emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
}
//std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
{
mavlink_local_position_ned_t pos;
mavlink_msg_local_position_ned_decode(&message, &pos);
quint64 time = getUnixTime(pos.time_boot_ms);
emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time);
if (!wrongComponent)
{
localX = pos.x;
localY = pos.y;
localZ = pos.z;
emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
// Set internal state
if (!positionLock) {
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
positionLock = true;
isLocalPositionKnown = true;
break;
case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
{
mavlink_global_vision_position_estimate_t pos;
mavlink_msg_global_vision_position_estimate_decode(&message, &pos);
quint64 time = getUnixTime(pos.usec);
emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time);
emit attitudeChanged(this, message.compid, pos.roll, pos.pitch, pos.yaw, time);
}
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
//std::cerr << std::endl;
//std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
{
mavlink_global_position_int_t pos;
mavlink_msg_global_position_int_decode(&message, &pos);
quint64 time = getUnixTime();
latitude = pos.lat/(double)1E7;
longitude = pos.lon/(double)1E7;
altitude = pos.alt/1000.0;
speedX = pos.vx/100.0;
speedY = pos.vy/100.0;
speedZ = pos.vz/100.0;
emit globalPositionChanged(this, latitude, longitude, altitude, time);
emit speedChanged(this, speedX, speedY, speedZ, time);
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
isGlobalPositionKnown = true;
//TODO fix this hack for forwarding of global position for patch antenna tracking
forwardMessage(message);
}
break;
case MAVLINK_MSG_ID_GPS_RAW_INT:
{
mavlink_gps_raw_int_t pos;
mavlink_msg_gps_raw_int_decode(&message, &pos);
// SANITY CHECK
// only accept values in a realistic range
// quint64 time = getUnixTime(pos.time_usec);
quint64 time = getUnixTime(pos.time_usec);
emit gpsLocalizationChanged(this, pos.fix_type);
// TODO: track localization state not only for gps but also for other loc. sources
int loc_type = pos.fix_type;
if (loc_type == 1)
{
loc_type = 0;
}
emit localizationChanged(this, loc_type);
emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
latitude = pos.lat/(double)1E7;
longitude = pos.lon/(double)1E7;
altitude = pos.alt/1000.0;
positionLock = true;
// Check for NaN
int alt = pos.alt;
if (!isnan(alt) && !isinf(alt))
alt = 0;
//emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE");
}
// FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
// Smaller than threshold and not NaN
if (vel < 1000000 && !isnan(vel) && !isinf(vel))
{
// FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time);
//qDebug() << "GOT GPS RAW";
// emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
}
else
{
emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
case MAVLINK_MSG_ID_GPS_STATUS:
{
mavlink_gps_status_t pos;
mavlink_msg_gps_status_decode(&message, &pos);
for(int i = 0; i < (int)pos.satellites_visible; i++)
{
emit gpsSatelliteStatusChanged(uasId, (unsigned char)pos.satellite_prn[i], (unsigned char)pos.satellite_elevation[i], (unsigned char)pos.satellite_azimuth[i], (unsigned char)pos.satellite_snr[i], static_cast<bool>(pos.satellite_used[i]));
case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
{
mavlink_gps_global_origin_t pos;
mavlink_msg_gps_global_origin_decode(&message, &pos);
emit homePositionChanged(uasId, pos.latitude / 10000000.0, pos.longitude / 10000000.0, pos.altitude / 1000.0);
case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
{
mavlink_rc_channels_raw_t channels;
mavlink_msg_rc_channels_raw_decode(&message, &channels);
emit remoteControlRSSIChanged(channels.rssi/255.0f);
emit remoteControlChannelRawChanged(0, channels.chan1_raw);
emit remoteControlChannelRawChanged(1, channels.chan2_raw);
emit remoteControlChannelRawChanged(2, channels.chan3_raw);
emit remoteControlChannelRawChanged(3, channels.chan4_raw);
emit remoteControlChannelRawChanged(4, channels.chan5_raw);
emit remoteControlChannelRawChanged(5, channels.chan6_raw);
emit remoteControlChannelRawChanged(6, channels.chan7_raw);
emit remoteControlChannelRawChanged(7, channels.chan8_raw);
}
case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
{
mavlink_rc_channels_scaled_t channels;
mavlink_msg_rc_channels_scaled_decode(&message, &channels);
emit remoteControlRSSIChanged(channels.rssi/255.0f);
emit remoteControlChannelScaledChanged(0, channels.chan1_scaled/10000.0f);
emit remoteControlChannelScaledChanged(1, channels.chan2_scaled/10000.0f);
emit remoteControlChannelScaledChanged(2, channels.chan3_scaled/10000.0f);
emit remoteControlChannelScaledChanged(3, channels.chan4_scaled/10000.0f);
emit remoteControlChannelScaledChanged(4, channels.chan5_scaled/10000.0f);
emit remoteControlChannelScaledChanged(5, channels.chan6_scaled/10000.0f);
emit remoteControlChannelScaledChanged(6, channels.chan7_scaled/10000.0f);
emit remoteControlChannelScaledChanged(7, channels.chan8_scaled/10000.0f);
}
case MAVLINK_MSG_ID_PARAM_VALUE:
{
mavlink_param_value_t value;
mavlink_msg_param_value_decode(&message, &value);
QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
// Construct a string stopping at the first NUL (0) character, else copy the whole
// byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe)
QString parameterName(bytes);
int component = message.compid;
mavlink_param_union_t val;
val.param_float = value.param_value;
val.type = value.param_type;
// Insert component if necessary
if (!parameters.contains(component))
{
parameters.insert(component, new QMap<QString, QVariant>());
}
lm
committed
// Insert parameter into registry
if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
lm
committed
// Insert with correct type
switch (value.param_type)
{
case MAV_PARAM_TYPE_REAL32:
{
// Variant
QVariant param(val.param_float);
parameters.value(component)->insert(parameterName, param);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
Lorenz Meier
committed
// qDebug() << "RECEIVED PARAM:" << param;
case MAV_PARAM_TYPE_UINT32:
{
// Variant
QVariant param(val.param_uint32);
parameters.value(component)->insert(parameterName, param);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
Lorenz Meier
committed
// qDebug() << "RECEIVED PARAM:" << param;
case MAV_PARAM_TYPE_INT32:
{
// Variant
QVariant param(val.param_int32);
parameters.value(component)->insert(parameterName, param);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
Lorenz Meier
committed
// qDebug() << "RECEIVED PARAM:" << param;
}
break;
default:
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
}
}
mavlink_command_ack_t ack;
mavlink_msg_command_ack_decode(&message, &ack);
switch (ack.result)
{
case MAV_RESULT_ACCEPTED:
{
emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
}
break;
case MAV_RESULT_TEMPORARILY_REJECTED:
{
emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Temporarily rejected CMD: %1").arg(ack.command));
}
break;
case MAV_RESULT_DENIED:
{
emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Denied CMD: %1").arg(ack.command));
}
break;
case MAV_RESULT_UNSUPPORTED:
{
emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Unsupported CMD: %1").arg(ack.command));
}
break;
case MAV_RESULT_FAILED:
{
emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Failed CMD: %1").arg(ack.command));
}
break;
}
}
case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
{
mavlink_roll_pitch_yaw_thrust_setpoint_t out;
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
quint64 time = getUnixTimeFromMs(out.time_boot_ms);
emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
}
{
mavlink_mission_count_t wpc;
mavlink_msg_mission_count_decode(&message, &wpc);
if(wpc.target_system == mavlink->getSystemId() || wpc.target_system == 0)
{
waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
qDebug() << "Got waypoint message, but was wrong system id" << wpc.target_system;
{
mavlink_mission_item_t wp;
mavlink_msg_mission_item_decode(&message, &wp);
//qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
if(wp.target_system == mavlink->getSystemId() || wp.target_system == 0)
{
waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
}
else
{
qDebug() << "Got waypoint message, but was wrong system id" << wp.target_system;
{
mavlink_mission_ack_t wpa;
mavlink_msg_mission_ack_decode(&message, &wpa);
if((wpa.target_system == mavlink->getSystemId() || wpa.target_system == 0) &&
(wpa.target_component == mavlink->getComponentId() || wpa.target_component == 0))
{
waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
{
mavlink_mission_request_t wpr;
mavlink_msg_mission_request_decode(&message, &wpr);
if(wpr.target_system == mavlink->getSystemId() || wpr.target_system == 0)
{
waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
qDebug() << "Got waypoint message, but was wrong system id" << wpr.target_system;
{
mavlink_mission_item_reached_t wpr;
mavlink_msg_mission_item_reached_decode(&message, &wpr);
waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq);
GAudioOutput::instance()->say(text);
emit textMessageReceived(message.sysid, message.compid, 0, text);
}