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"
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
uasId(id),
startTime(QGC::groundTimeMilliseconds()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(-1),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
waypointManager(*this),
thrustSum(0),
thrustMax(10),
startVoltage(0),
warnVoltage(9.5f),
warnLevelPercent(20.0f),
currentVoltage(12.0f),
lpVoltage(12.0f),
batteryRemainingEstimateEnabled(false),
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)),
paramsOnceRequested(false),
airframe(0),
attitudeKnown(false),
color = UASInterface::getNextColor();
connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
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();
}
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();
if (settings.contains("BATTERY_SPECS")) {
setBatterySpecs(settings.value("BATTERY_SPECS").toString());
}
settings.endGroup();
}
int UAS::getUASID() const
void UAS::updateState()
{
// Check if heartbeat timed out
quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
if (heartbeatInterval > timeoutIntervalHeartbeat)
{
emit heartbeatTimeout(heartbeatInterval);
emit heartbeatTimeout();
}
// Position lock is set by the MAVLink message handler
// if no position lock is available, indicate an error
positionLock = false;
}
else
{
if ((mode == (int)MAV_MODE_AUTO || mode == (int)MAV_MODE_GUIDED) && positionLock)
{
GAudioOutput::instance()->notifyNegative();
}
}
}
if (UASManager::instance()->getActiveUAS() != this) {
UASManager::instance()->setActiveUAS(this);
emit systemSelected(true);
}
}
bool UAS::getSelected() const
{
return (UASManager::instance()->getActiveUAS() == this);
void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
{
mavlink_named_value_float_t val;
mavlink_msg_named_value_float_decode(&message, &val);
QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
}
else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
{
mavlink_named_value_int_t val;
mavlink_msg_named_value_int_decode(&message, &val);
QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN);
emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
}
}
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
if (!links->contains(link))
{
// qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
// else
// {
// qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
// }
// 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))
{
switch (message.msgid)
{
mavlink_heartbeat_t state;
mavlink_msg_heartbeat_decode(&message, &state);
{
if (airframe == 0)
{
switch (type)
{
setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
break;
setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
break;
default:
// Do nothing
break;
}
}
Mariano Lizarraga
committed
QString audiostring = "System " + getUASName();
QString stateAudio = "";
QString modeAudio = "";
QString navModeAudio = "";
bool statechanged = false;
bool modechanged = false;
if (state.system_status != this->status)
{
statechanged = true;
this->status = state.system_status;
getStatusForCode((int)state.system_status, uasState, stateDescription);
emit statusChanged(this, uasState, stateDescription);
emit statusChanged(this->status);
stateAudio = tr(" changed status to ") + uasState;
}
if (this->mode != static_cast<int>(state.system_mode))
{
modechanged = true;
this->mode = static_cast<int>(state.system_mode);
Mariano Lizarraga
committed
shortModeText = getShortModeTextFor(this->mode);
Mariano Lizarraga
committed
emit modeChanged(this->getUASID(), shortModeText, "");
modeAudio = " is now in " + shortModeText;
}
if (navMode != state.flight_mode)
{
emit navModeChanged(uasId, state.flight_mode, getNavModeText(state.flight_mode));
navMode = state.flight_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 ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY)
{
GAudioOutput::instance()->startEmergency();
}
else if (modechanged || statechanged)
{
GAudioOutput::instance()->stopEmergency();
GAudioOutput::instance()->say(audiostring);
}
if (state.system_status == MAV_STATE_POWEROFF)
{
emit systemRemoved(this);
emit systemRemoved();
}
}
break;
case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
case MAVLINK_MSG_ID_NAMED_VALUE_INT:
// Receive named value message
receiveMessageNamedValue(message);
break;
case MAVLINK_MSG_ID_SYS_STATUS:
{
mavlink_sys_status_t state;
mavlink_msg_sys_status_decode(&message, &state);
emit loadChanged(this,state.load/10.0f);
emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime());
Mariano Lizarraga
committed
currentVoltage = state.voltage_battery/1000.0f;
lpVoltage = filterVoltage(currentVoltage);
if (startVoltage == 0) startVoltage = currentVoltage;
timeRemaining = calculateTimeRemaining();
if (!batteryRemainingEstimateEnabled)
{
chargeLevel = state.battery_percent/2.55f;
}
//qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
emit voltageChanged(message.sysid, state.battery_percent/2.55f);
Mariano Lizarraga
committed
if (lpVoltage < warnVoltage)
{
}
else
{
Mariano Lizarraga
committed
emit dropRateChanged(this->getUASID(), state.errors_uart/1000.0f);
#ifdef MAVLINK_ENABLED_PIXHAWK
case MAVLINK_MSG_ID_CONTROL_STATUS:
{
mavlink_control_status_t status;
mavlink_msg_control_status_decode(&message, &status);
// Emit control status vector
emit attitudeControlEnabled(static_cast<bool>(status.control_att));
emit positionXYControlEnabled(static_cast<bool>(status.control_pos_xy));
emit positionZControlEnabled(static_cast<bool>(status.control_pos_z));
emit positionYawControlEnabled(static_cast<bool>(status.control_pos_yaw));
// Emit localization status vector
emit localizationChanged(this, status.position_fix);
emit visionLocalizationChanged(this, status.vision_fix);
emit gpsLocalizationChanged(this, status.gps_fix);
}
break;
case MAVLINK_MSG_ID_RAW_IMU:
{
mavlink_raw_imu_t raw;
mavlink_msg_raw_imu_decode(&message, &raw);
quint64 time = getUnixTime(raw.usec);
emit valueChanged(uasId, "accel x", "raw", static_cast<double>(raw.xacc), time);
emit valueChanged(uasId, "accel y", "raw", static_cast<double>(raw.yacc), time);
emit valueChanged(uasId, "accel z", "raw", static_cast<double>(raw.zacc), time);
emit valueChanged(uasId, "gyro roll", "raw", static_cast<double>(raw.xgyro), time);
emit valueChanged(uasId, "gyro pitch", "raw", static_cast<double>(raw.ygyro), time);
emit valueChanged(uasId, "gyro yaw", "raw", static_cast<double>(raw.zgyro), time);
emit valueChanged(uasId, "mag x", "raw", static_cast<double>(raw.xmag), time);
emit valueChanged(uasId, "mag y", "raw", static_cast<double>(raw.ymag), time);
emit valueChanged(uasId, "mag z", "raw", static_cast<double>(raw.zmag), time);
}
break;
case MAVLINK_MSG_ID_SCALED_IMU:
{
mavlink_scaled_imu_t scaled;
mavlink_msg_scaled_imu_decode(&message, &scaled);
quint64 time = getUnixTime(scaled.usec);
emit valueChanged(uasId, "accel x", "g", scaled.xacc/1000.0f, time);
emit valueChanged(uasId, "accel y", "g", scaled.yacc/1000.0f, time);
emit valueChanged(uasId, "accel z", "g", scaled.zacc/1000.0f, time);
emit valueChanged(uasId, "gyro roll", "rad/s", scaled.xgyro/1000.0f, time);
emit valueChanged(uasId, "gyro pitch", "rad/s", scaled.ygyro/1000.0f, time);
emit valueChanged(uasId, "gyro yaw", "rad/s", scaled.zgyro/1000.0f, time);
emit valueChanged(uasId, "mag x", "uTesla", scaled.xmag/100.0f, time);
emit valueChanged(uasId, "mag y", "uTesla", scaled.ymag/100.0f, time);
emit valueChanged(uasId, "mag z", "uTesla", scaled.zmag/100.0f, 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_attitude_t attitude;
mavlink_msg_attitude_decode(&message, &attitude);
quint64 time = getUnixReferenceTime(attitude.usec);
lastAttitude = time;
roll = QGC::limitAngleToPMPIf(attitude.roll);
pitch = QGC::limitAngleToPMPIf(attitude.pitch);
yaw = QGC::limitAngleToPMPIf(attitude.yaw);
emit valueChanged(uasId, "roll", "rad", roll, time);
emit valueChanged(uasId, "pitch", "rad", pitch, time);
emit valueChanged(uasId, "yaw", "rad", yaw, time);
emit valueChanged(uasId, "rollspeed", "rad/s", attitude.rollspeed, time);
emit valueChanged(uasId, "pitchspeed", "rad/s", attitude.pitchspeed, time);
emit valueChanged(uasId, "yawspeed", "rad/s", attitude.yawspeed, time);
// Emit in angles
// Convert yaw angle to compass value
// in 0 - 360 deg range
float compass = (yaw/M_PI)*180.0+360.0f;
while (compass > 360.0f) {
compass -= 360.0f;
}
emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time);
emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time);
emit valueChanged(uasId, "heading deg", "deg", compass, time);
emit valueChanged(uasId, "rollspeed d/s", "deg/s", (attitude.rollspeed/M_PI)*180.0, time);
emit valueChanged(uasId, "pitchspeed d/s", "deg/s", (attitude.pitchspeed/M_PI)*180.0, time);
emit valueChanged(uasId, "yawspeed d/s", "deg/s", (attitude.yawspeed/M_PI)*180.0, time);
emit attitudeChanged(this, roll, pitch, yaw, time);
emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
case MAVLINK_MSG_ID_HIL_CONTROLS:
{
mavlink_hil_controls_t hil;
mavlink_msg_hil_controls_decode(&message, &hil);
emit hilControlsChanged(hil.time_us, hil.roll_ailerons, hil.pitch_elevator, hil.yaw_rudder, hil.throttle, hil.mode, hil.nav_mode);
}
break;
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 valueChanged(uasId, "airspeed", "m/s", hud.airspeed, time);
emit valueChanged(uasId, "groundspeed", "m/s", hud.groundspeed, time);
emit valueChanged(uasId, "altitude", "m", hud.alt, time);
emit valueChanged(uasId, "heading", "deg", hud.heading, time);
emit valueChanged(uasId, "climbrate", "m/s", hud.climb, time);
emit valueChanged(uasId, "throttle", "%", hud.throttle, time);
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);
//yaw = (hud.heading-180.0f/360.0f)*M_PI;
//emit attitudeChanged(this, roll, pitch, yaw, getUnixTime());
emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, getUnixTime());
}
break;
case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
{
mavlink_nav_controller_output_t nav;
mavlink_msg_nav_controller_output_decode(&message, &nav);
quint64 time = getUnixTime();
// Update UI
emit valueChanged(uasId, "nav roll", "deg", nav.nav_roll, time);
emit valueChanged(uasId, "nav pitch", "deg", nav.nav_pitch, time);
emit valueChanged(uasId, "nav bearing", "deg", nav.nav_bearing, time);
emit valueChanged(uasId, "target bearing", "deg", nav.target_bearing, time);
emit valueChanged(uasId, "wp dist", "m", nav.wp_dist, time);
emit valueChanged(uasId, "alt err", "m", nav.alt_error, time);
emit valueChanged(uasId, "airspeed err", "m/s", nav.alt_error, time);
emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time);
}
break;
case MAVLINK_MSG_ID_LOCAL_POSITION:
//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;
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
{
mavlink_local_position_t pos;
mavlink_msg_local_position_decode(&message, &pos);
quint64 time = getUnixTime(pos.usec);
localX = pos.x;
localY = pos.y;
localZ = pos.z;
emit valueChanged(uasId, "x", "m", pos.x, time);
emit valueChanged(uasId, "y", "m", pos.y, time);
emit valueChanged(uasId, "z", "m", pos.z, time);
emit valueChanged(uasId, "x speed", "m/s", pos.vx, time);
emit valueChanged(uasId, "y speed", "m/s", pos.vy, time);
emit valueChanged(uasId, "z speed", "m/s", pos.vz, time);
emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
// qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
// qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
//emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
// Set internal state
if (!positionLock) {
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
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 valueChanged(uasId, "latitude", "deg", latitude, time);
emit valueChanged(uasId, "longitude", "deg", longitude, time);
emit valueChanged(uasId, "altitude", "m", altitude, time);
double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
emit globalPositionChanged(this, latitude, longitude, altitude, time);
emit speedChanged(this, speedX, speedY, speedZ, time);
// Set internal state
if (!positionLock) {
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
//TODO fix this hack for forwarding of global position for patch antenna tracking
forwardMessage(message);
case MAVLINK_MSG_ID_GLOBAL_POSITION:
{
mavlink_global_position_t pos;
mavlink_msg_global_position_decode(&message, &pos);
quint64 time = getUnixTime();
latitude = pos.lat;
longitude = pos.lon;
altitude = pos.alt;
speedX = pos.vx;
speedY = pos.vy;
speedZ = pos.vz;
emit valueChanged(uasId, "latitude", "deg", latitude, time);
emit valueChanged(uasId, "longitude", "deg", longitude, time);
emit valueChanged(uasId, "altitude", "m", altitude, time);
double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
emit globalPositionChanged(this, latitude, longitude, altitude, time);
emit speedChanged(this, speedX, speedY, speedZ, time);
// Set internal state
if (!positionLock) {
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
573
574
575
576
577
578
579
580
581
582
583
584
585
586
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
positionLock = true;
//TODO fix this hack for forwarding of global position for patch antenna tracking
forwardMessage(message);
}
break;
case MAVLINK_MSG_ID_GPS_RAW:
//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_gps_raw_t pos;
mavlink_msg_gps_raw_decode(&message, &pos);
// SANITY CHECK
// only accept values in a realistic range
// quint64 time = getUnixTime(pos.usec);
quint64 time = getUnixTime();
emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
if (pos.fix_type > 0) {
emit valueChanged(uasId, "gps speed", "m/s", pos.v, time);
latitude = pos.lat;
longitude = pos.lon;
altitude = pos.alt;
positionLock = true;
// Check for NaN
int alt = pos.alt;
if (alt != alt) {
alt = 0;
emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
}
emit valueChanged(uasId, "altitude", "m", pos.alt, time);
// Smaller than threshold and not NaN
if (pos.v < 1000000 && pos.v == pos.v) {
emit valueChanged(uasId, "speed", "m/s", pos.v, 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(pos.v));
}
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.usec);
emit valueChanged(uasId, "latitude", "deg", pos.lat/(double)1E7, time);
emit valueChanged(uasId, "longitude", "deg", pos.lon/(double)1E7, time);
emit valueChanged(uasId, "eph", "m", pos.eph/(double)1E2, time);
emit valueChanged(uasId, "epv", "m", pos.eph/(double)1E2, time);
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 (alt != alt) {
alt = 0;
emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
}
emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
// Smaller than threshold and not NaN
float vel = pos.vel/100.0f;
if (vel < 1000000 && !isnan(vel) && !isinf(vel)) {
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_LOCAL_ORIGIN_SET:
{
mavlink_gps_local_origin_set_t pos;
mavlink_msg_gps_local_origin_set_decode(&message, &pos);
emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
case MAVLINK_MSG_ID_RAW_PRESSURE:
{
mavlink_raw_pressure_t pressure;
mavlink_msg_raw_pressure_decode(&message, &pressure);
quint64 time = this->getUnixTime(pressure.usec);
emit valueChanged(uasId, "abs pressure", "raw", pressure.press_abs, time);
emit valueChanged(uasId, "diff pressure 1", "raw", pressure.press_diff1, time);
emit valueChanged(uasId, "diff pressure 2", "raw", pressure.press_diff2, time);
emit valueChanged(uasId, "temperature", "raw", pressure.temperature, time);
}
break;
case MAVLINK_MSG_ID_SCALED_PRESSURE:
{
mavlink_scaled_pressure_t pressure;
mavlink_msg_scaled_pressure_decode(&message, &pressure);
quint64 time = this->getUnixTime(pressure.usec);
emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time);
emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time);
}
break;
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);
quint64 time = getUnixTime();
emit valueChanged(uasId, "rc in #1", "us", channels.chan1_raw, time);
emit valueChanged(uasId, "rc in #2", "us", channels.chan2_raw, time);
emit valueChanged(uasId, "rc in #3", "us", channels.chan3_raw, time);
emit valueChanged(uasId, "rc in #4", "us", channels.chan4_raw, time);
emit valueChanged(uasId, "rc in #5", "us", channels.chan5_raw, time);
emit valueChanged(uasId, "rc in #6", "us", channels.chan6_raw, time);
emit valueChanged(uasId, "rc in #7", "us", channels.chan7_raw, time);
emit valueChanged(uasId, "rc in #8", "us", channels.chan8_raw, time);
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((char*)value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
QString parameterName = QString(bytes);
int component = message.compid;
mavlink_param_union_t val;
val.param_float = value.param_value;
// Convert to machine order if necessary
//#if MAVLINK_NEED_BYTE_SWAP
// buffer[bindex] = (b>>24)&0xff;
// buffer[bindex+1] = (b>>16)&0xff;
// buffer[bindex+2] = (b>>8)&0xff;
// buffer[bindex+3] = (b & 0xff);
//#else
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
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
// Insert with correct type
switch (value.param_type)
{
case MAV_DATA_TYPE_FLOAT:
parameters.value(component)->insert(parameterName, val.param_float);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_float);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_float);
break;/*
case MAV_DATA_TYPE_UINT8:
parameters.value(component)->insert(parameterName, val.param_uint8);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_uint8);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint8);
break;
case MAV_DATA_TYPE_INT8:
parameters.value(component)->insert(parameterName, val.param_int8);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_int8);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int8);
break;
case MAV_DATA_TYPE_UINT16:
parameters.value(component)->insert(parameterName, val.param_uint16);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_uint16);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint16);
break;
case MAV_DATA_TYPE_INT16:
parameters.value(component)->insert(parameterName, val.param_int16);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_int16);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int16);
break;*/
case MAV_DATA_TYPE_UINT32:
parameters.value(component)->insert(parameterName, val.param_uint32);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_uint32);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint32);
break;
case MAV_DATA_TYPE_INT32:
parameters.value(component)->insert(parameterName, val.param_int32);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_int32);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int32);
break;
default:
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
}
case MAVLINK_MSG_ID_COMMAND_ACK:
mavlink_command_ack_t ack;
mavlink_msg_command_ack_decode(&message, &ack);
if (ack.result == 1)
{
emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
}
else
{
emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
}
break;
emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), "raw", mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow());
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 = getUnixTime(out.time_ms*1000);
emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
emit valueChanged(uasId, "att control roll", "rad", out.roll, time);
emit valueChanged(uasId, "att control pitch", "rad", out.pitch, time);
emit valueChanged(uasId, "att control yaw", "rad", out.yaw, time);
emit valueChanged(uasId, "att control thrust", "0-1", out.thrust, time);
case MAVLINK_MSG_ID_WAYPOINT_COUNT:
{
mavlink_waypoint_count_t wpc;
mavlink_msg_waypoint_count_decode(&message, &wpc);
if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
{
waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
}
else
{
qDebug() << "Got waypoint message, but was not for me";
}
case MAVLINK_MSG_ID_WAYPOINT:
{
mavlink_waypoint_t wp;
mavlink_msg_waypoint_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_component == mavlink->getComponentId())
{
waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
}
else
{
qDebug() << "Got waypoint message, but was not for me";
}
case MAVLINK_MSG_ID_WAYPOINT_ACK:
{
mavlink_waypoint_ack_t wpa;
mavlink_msg_waypoint_ack_decode(&message, &wpa);
if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
{
waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
}
case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
{
mavlink_waypoint_request_t wpr;
mavlink_msg_waypoint_request_decode(&message, &wpr);
if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
{
waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
}
else
{
qDebug() << "Got waypoint message, but was not for me";
}
case MAVLINK_MSG_ID_WAYPOINT_REACHED:
{
mavlink_waypoint_reached_t wpr;
mavlink_msg_waypoint_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);
}
break;
case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
{
mavlink_waypoint_current_t wpc;
mavlink_msg_waypoint_current_decode(&message, &wpc);
waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
}
break;
case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
{
mavlink_local_position_setpoint_t p;
mavlink_msg_local_position_setpoint_decode(&message, &p);
emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs());
}
break;
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
{
mavlink_servo_output_raw_t servos;
mavlink_msg_servo_output_raw_decode(&message, &servos);
quint64 time = getUnixTime();
emit valueChanged(uasId, "servo #1", "us", servos.servo1_raw, time);
emit valueChanged(uasId, "servo #2", "us", servos.servo2_raw, time);
emit valueChanged(uasId, "servo #3", "us", servos.servo3_raw, time);
emit valueChanged(uasId, "servo #4", "us", servos.servo4_raw, time);
emit valueChanged(uasId, "servo #5", "us", servos.servo5_raw, time);
emit valueChanged(uasId, "servo #6", "us", servos.servo6_raw, time);
emit valueChanged(uasId, "servo #7", "us", servos.servo7_raw, time);
emit valueChanged(uasId, "servo #8", "us", servos.servo8_raw, time);
}
break;
case MAVLINK_MSG_ID_STATUSTEXT:
{
QByteArray b;
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
//b.append('\0');
QString text = QString(b);
int severity = mavlink_msg_statustext_get_severity(&message);
//qDebug() << "RECEIVED STATUS:" << text;false
//emit statusTextReceived(severity, text);
emit textMessageReceived(uasId, message.compid, severity, text);
}
break;
#ifdef MAVLINK_ENABLED_PIXHAWK
case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
{
qDebug() << "RECIEVED ACK TO GET IMAGE";
mavlink_data_transmission_handshake_t p;
mavlink_msg_data_transmission_handshake_decode(&message, &p);
imageSize = p.size;
imagePackets = p.packets;
imagePayload = p.payload;
imageQuality = p.jpg_quality;
imageType = p.type;
imageStart = QGC::groundTimeMilliseconds();
}
break;
case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
{
mavlink_encapsulated_data_t img;
mavlink_msg_encapsulated_data_decode(&message, &img);
int seq = img.seqnr;
int pos = seq * imagePayload;
// Check if we have a valid transaction
if (imagePackets == 0)
{
// NO VALID TRANSACTION - ABORT
// Restart statemachine
imagePacketsArrived = 0;
for (int i = 0; i < imagePayload; ++i)
{
if (pos <= imageSize) {
imageRecBuffer[pos] = img.data[i];
}
++pos;
}