UAS.cc 92.9 KB
Newer Older
1
/*===================================================================
pixhawk's avatar
pixhawk committed
2 3 4 5 6 7 8 9 10 11 12 13 14
======================================================================*/

/**
 * @file
 *   @brief Represents one unmanned aerial vehicle
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <QList>
#include <QMessageBox>
#include <QTimer>
15
#include <QSettings>
pixhawk's avatar
pixhawk committed
16 17 18
#include <iostream>
#include <QDebug>
#include <cmath>
19
#include <qmath.h>
pixhawk's avatar
pixhawk committed
20 21 22
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
23
#include "QGC.h"
pixhawk's avatar
pixhawk committed
24
#include "GAudioOutput.h"
25
#include "MAVLinkProtocol.h"
pixhawk's avatar
pixhawk committed
26
#include "QGCMAVLink.h"
27 28
#include "LinkManager.h"
#include "SerialLink.h"
pixhawk's avatar
pixhawk committed
29

30
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
LM's avatar
LM committed
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),
LM's avatar
LM committed
77 78 79
paramManager(NULL),
attitudeStamped(true),
lastAttitude(0)
pixhawk's avatar
pixhawk committed
80
{
81
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
82
    setBattery(LIPOLY, 3);
83
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
84
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
85
    statusTimeout->start(500);
86
    readSettings();
pixhawk's avatar
pixhawk committed
87 88 89 90
}

UAS::~UAS()
{
91
    writeSettings();
pixhawk's avatar
pixhawk committed
92
    delete links;
93
    links=NULL;
pixhawk's avatar
pixhawk committed
94 95
}

96 97 98 99 100
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
101 102
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
103
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
104 105 106 107 108 109 110 111 112
    settings.endGroup();
    settings.sync();
}

void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
113 114
    this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
    this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
115
    if (settings.contains("BATTERY_SPECS")) {
116 117
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
118 119 120
    settings.endGroup();
}

121
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
122 123 124 125
{
    return uasId;
}

126 127
void UAS::updateState()
{
128 129
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
130
    if (heartbeatInterval > timeoutIntervalHeartbeat) {
131 132 133 134
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

135 136
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
137
    if (positionLock) {
138
        positionLock = false;
139 140
    } else {
        if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock) {
141 142 143 144 145
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
146 147
void UAS::setSelected()
{
148
    if (UASManager::instance()->getActiveUAS() != this) {
149 150 151 152 153 154 155 156
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

bool UAS::getSelected() const
{
    return (UASManager::instance()->getActiveUAS() == this);
pixhawk's avatar
pixhawk committed
157 158
}

159 160
void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
161 162
    if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
    {
pixhawk's avatar
pixhawk committed
163 164
        mavlink_named_value_float_t val;
        mavlink_msg_named_value_float_decode(&message, &val);
lm's avatar
lm committed
165 166
        QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
        emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
167 168 169
    }
    else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
    {
pixhawk's avatar
pixhawk committed
170 171
        mavlink_named_value_int_t val;
        mavlink_msg_named_value_int_decode(&message, &val);
lm's avatar
lm committed
172 173
        QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN);
        emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
174 175 176
    }
}

pixhawk's avatar
pixhawk committed
177 178
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
179
    if (!link) return;
180 181
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
182
        addLink(link);
183
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
184
    }
185 186 187 188
    //    else
    //    {
    //        qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
    //    }
pixhawk's avatar
pixhawk committed
189

190
    //    qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;
pixhawk's avatar
pixhawk committed
191

LM's avatar
LM committed
192 193 194 195
    // 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))
196
    {
pixhawk's avatar
pixhawk committed
197 198
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
199

200 201
        switch (message.msgid)
        {
pixhawk's avatar
pixhawk committed
202
        case MAVLINK_MSG_ID_HEARTBEAT:
203
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
204 205
            emit heartbeat(this);
            // Set new type if it has changed
206 207
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
            {
pixhawk's avatar
pixhawk committed
208
                this->type = mavlink_msg_heartbeat_get_type(&message);
209 210 211 212
                if (airframe == 0)
                {
                    switch (type)
                    {
213 214 215 216 217 218 219 220 221 222 223
                    case MAV_FIXED_WING:
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
                    case MAV_QUADROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
                    default:
                        // Do nothing
                        break;
                    }
                }
224
                this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
pixhawk's avatar
pixhawk committed
225 226
                emit systemTypeSet(this, type);
            }
227

228 229 230 231 232
            break;
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
            // Receive named value message
            receiveMessageNamedValue(message);
pixhawk's avatar
pixhawk committed
233 234 235 236 237 238
            break;
        case MAVLINK_MSG_ID_BOOT:
            getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);
            emit statusChanged(this, uasState, stateDescription);
            onboardTimeOffset = 0; // Reset offset measurement
            break;
239 240
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
LM's avatar
LM committed
241 242 243 244 245 246 247 248 249 250 251 252
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);

                // FIXME
                //qDebug() << "1 SYSTEM STATUS:" << state.status;

                QString audiostring = "System " + getUASName();
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;

253 254
                if (state.status != this->status)
                {
LM's avatar
LM committed
255 256 257 258 259 260
                    statechanged = true;
                    this->status = state.status;
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
                    emit statusChanged(this->status);

261 262
                    shortStateText = uasState;

LM's avatar
LM committed
263 264
                    stateAudio = " changed status to " + uasState;
                }
265

266 267
                if (navMode != state.nav_mode)
                {
LM's avatar
LM committed
268 269 270
                    emit navModeChanged(uasId, state.nav_mode, getNavModeText(state.nav_mode));
                    navMode = state.nav_mode;
                }
lm's avatar
lm committed
271

LM's avatar
LM committed
272
                emit loadChanged(this,state.load/10.0f);
273
                //emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime());
pixhawk's avatar
pixhawk committed
274

275 276
                if (this->mode != static_cast<int>(state.mode))
                {
LM's avatar
LM committed
277 278 279
                    modechanged = true;
                    this->mode = static_cast<int>(state.mode);
                    QString mode;
280

LM's avatar
LM committed
281 282 283 284 285 286 287
                    switch (state.mode) {
                    case (uint8_t)MAV_MODE_LOCKED:
                        mode = "LOCKED MODE";
                        break;
                    case (uint8_t)MAV_MODE_MANUAL:
                        mode = "MANUAL MODE";
                        break;
288

289
#ifdef MAVLINK_ENABLED_SLUGS
LM's avatar
LM committed
290 291 292 293 294 295 296 297 298 299 300 301 302
                    case (uint8_t)MAV_MODE_AUTO:
                        mode = "WAYPOINT MODE";
                        break;
                    case (uint8_t)MAV_MODE_GUIDED:
                        mode = "MID-L CMDS MODE";
                        break;

                    case (uint8_t)MAV_MODE_TEST1:
                        mode = "PASST MODE";
                        break;
                    case (uint8_t)MAV_MODE_TEST2:
                        mode = "SEL PT MODE";
                        break;
303
#else
LM's avatar
LM committed
304 305 306 307 308 309 310 311 312 313 314 315 316
                    case (uint8_t)MAV_MODE_AUTO:
                        mode = "AUTO MODE";
                        break;
                    case (uint8_t)MAV_MODE_GUIDED:
                        mode = "GUIDED MODE";
                        break;

                    case (uint8_t)MAV_MODE_TEST1:
                        mode = "TEST1 MODE";
                        break;
                    case (uint8_t)MAV_MODE_TEST2:
                        mode = "TEST2 MODE";
                        break;
317
#endif
LM's avatar
LM committed
318 319 320
                    case (uint8_t)MAV_MODE_READY:
                        mode = "READY MODE";
                        break;
321

LM's avatar
LM committed
322 323 324
                    case (uint8_t)MAV_MODE_TEST3:
                        mode = "TEST3 MODE";
                        break;
325

LM's avatar
LM committed
326 327 328 329 330 331 332
                    case (uint8_t)MAV_MODE_RC_TRAINING:
                        mode = "RC TRAINING MODE";
                        break;
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }
lm's avatar
lm committed
333

334 335
                    shortModeText = mode;

LM's avatar
LM committed
336
                    emit modeChanged(this->getUASID(), mode, "");
337

LM's avatar
LM committed
338
                    //qDebug() << "2 SYSTEM MODE:" << mode;
339

LM's avatar
LM committed
340 341 342 343 344 345
                    modeAudio = " is now in " + mode;
                }
                currentVoltage = state.vbat/1000.0f;
                lpVoltage = filterVoltage(currentVoltage);
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
346 347
                if (!batteryRemainingEstimateEnabled)
                {
LM's avatar
LM committed
348 349 350 351 352
                    chargeLevel = state.battery_remaining/10.0f;
                }
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
353

LM's avatar
LM committed
354
                // LOW BATTERY ALARM
355 356
                if (lpVoltage < warnVoltage)
                {
LM's avatar
LM committed
357
                    startLowBattAlarm();
358 359 360
                }
                else
                {
LM's avatar
LM committed
361 362
                    stopLowBattAlarm();
                }
363

LM's avatar
LM committed
364 365
                // COMMUNICATIONS DROP RATE
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
366 367


LM's avatar
LM committed
368 369
                //add for development
                //emit remoteControlRSSIChanged(state.packet_drop/1000.0f);
lm's avatar
lm committed
370

LM's avatar
LM committed
371 372 373
                //float en = state.packet_drop/1000.0f;
                //emit remoteControlChannelRawChanged(0, en);//MAVLINK_MSG_ID_RC_CHANNELS_RAW
                //emit remoteControlChannelScaledChanged(0, en/100.0f);//MAVLINK_MSG_ID_RC_CHANNELS_SCALED
374

James Goppert's avatar
James Goppert committed
375

LM's avatar
LM committed
376 377 378
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;

                // AUDIO
379 380
                if (modechanged && statechanged)
                {
LM's avatar
LM committed
381 382
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
383 384 385
                }
                else
                {
LM's avatar
LM committed
386 387 388
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
389 390
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
                {
LM's avatar
LM committed
391
                    GAudioOutput::instance()->startEmergency();
392 393 394
                }
                else if (modechanged || statechanged)
                {
LM's avatar
LM committed
395 396 397 398
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }

399 400
                if (state.status == MAV_STATE_POWEROFF)
                {
LM's avatar
LM committed
401 402 403
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
404
            }
LM's avatar
LM committed
405
            break;
406 407

#ifdef MAVLINK_ENABLED_PIXHAWK
408 409
        case MAVLINK_MSG_ID_CONTROL_STATUS:
            {
LM's avatar
LM committed
410 411 412 413 414 415 416 417 418 419 420 421 422 423
                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;
424 425 426 427 428 429 430 431 432 433
        case MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE:
            {
                mavlink_vision_speed_estimate_t speed;
                mavlink_msg_vision_speed_estimate_decode(&message, &speed);
                quint64 time = getUnixTime(speed.usec);
                emit valueChanged(uasId, "vis.speed x", "m/s", static_cast<double>(speed.x), time);
                emit valueChanged(uasId, "vis.speed y", "m/s", static_cast<double>(speed.y), time);
                emit valueChanged(uasId, "vis.speed z", "m/s", static_cast<double>(speed.z), time);
            }
            break;
lm's avatar
lm committed
434
#endif // PIXHAWK
435 436
        case MAVLINK_MSG_ID_RAW_IMU:
            {
LM's avatar
LM committed
437 438 439 440 441 442 443 444 445 446 447 448 449 450 451
                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;
452 453
        case MAVLINK_MSG_ID_SCALED_IMU:
            {
LM's avatar
LM committed
454 455 456 457 458 459 460 461 462 463
                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);
464 465 466
                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);
LM's avatar
LM committed
467 468
            }
            break;
pixhawk's avatar
pixhawk committed
469 470
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
471
            //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;
LM's avatar
LM committed
472 473 474
            {
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
LM's avatar
LM committed
475 476
                quint64 time = getUnixReferenceTime(attitude.usec);
                lastAttitude = time;
LM's avatar
LM committed
477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494
                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;
                }
lm's avatar
lm committed
495

LM's avatar
LM committed
496
                attitudeKnown = true;
lm's avatar
lm committed
497

LM's avatar
LM committed
498 499 500 501 502 503
                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);
504

505
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
506
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
507
            }
LM's avatar
LM committed
508
            break;
509 510
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
511 512 513 514 515 516 517 518 519 520 521 522
                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);

523 524
                if (!attitudeKnown)
                {
LM's avatar
LM committed
525 526 527
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
528

LM's avatar
LM committed
529 530
                emit altitudeChanged(uasId, hud.alt);
                //yaw = (hud.heading-180.0f/360.0f)*M_PI;
LM's avatar
LM committed
531
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
LM's avatar
LM committed
532 533
            }
            break;
534 535
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
            {
LM's avatar
LM committed
536 537 538 539 540 541 542 543 544 545 546 547 548 549
                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;
550
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
551
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
552
            //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;
LM's avatar
LM committed
553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578
            {
                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;
lm's avatar
lm committed
579
            }
LM's avatar
LM committed
580
            break;
581
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
582 583
            //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;
LM's avatar
LM committed
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
            {
                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);
609
            }
LM's avatar
LM committed
610
            break;
611 612
        case MAVLINK_MSG_ID_GLOBAL_POSITION:
            {
LM's avatar
LM committed
613 614 615
                mavlink_global_position_t pos;
                mavlink_msg_global_position_decode(&message, &pos);
                quint64 time = getUnixTime();
616 617 618
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
LM's avatar
LM committed
619 620 621 622 623 624 625 626 627 628 629 630 631 632
                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();
633
                }
LM's avatar
LM committed
634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675
                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));
                    }
676 677
                }
            }
LM's avatar
LM committed
678
            break;
679 680
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
LM's avatar
LM committed
681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714
                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);
                quint64 time = getUnixTime();

                emit valueChanged(uasId, "latitude", "deg", pos.lat/(double)1E7, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon/(double)1E7, time);

                if (pos.fix_type > 0) {
                    emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
                    emit valueChanged(uasId, "gps speed", "m/s", pos.v, 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
                    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));
                    }
lm's avatar
lm committed
715 716
                }
            }
LM's avatar
LM committed
717
            break;
718 719
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
LM's avatar
LM committed
720 721
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
722 723
                for(int i = 0; i < (int)pos.satellites_visible; i++)
                {
LM's avatar
LM committed
724 725
                    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]));
                }
726
            }
LM's avatar
LM committed
727
            break;
728 729
        case MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET:
            {
LM's avatar
LM committed
730 731
                mavlink_gps_local_origin_set_t pos;
                mavlink_msg_gps_local_origin_set_decode(&message, &pos);
LM's avatar
LM committed
732
                emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
LM's avatar
LM committed
733 734
            }
            break;
735 736
        case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
LM's avatar
LM committed
737 738 739 740 741 742 743 744 745
                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;
746

747 748
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
            {
LM's avatar
LM committed
749 750 751 752 753 754 755 756
                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;
757

758 759
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            {
LM's avatar
LM committed
760 761 762 763 764 765 766 767 768 769 770
                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);
771 772 773 774 775 776 777 778 779
                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);
LM's avatar
LM committed
780 781
            }
            break;
782 783
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
LM's avatar
LM committed
784 785 786 787 788 789 790 791 792 793 794
                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);
lm's avatar
lm committed
795
            }
LM's avatar
LM committed
796
            break;
797 798
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
LM's avatar
LM committed
799 800 801 802 803 804 805 806
                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;
                float val = value.param_value;

                // Insert component if necessary
807 808
                if (!parameters.contains(component))
                {
LM's avatar
LM committed
809 810
                    parameters.insert(component, new QMap<QString, float>());
                }
811

LM's avatar
LM committed
812 813 814
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
                parameters.value(component)->insert(parameterName, val);
815

LM's avatar
LM committed
816 817 818 819 820
                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, val);
                emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val);
            }
            break;
lm's avatar
lm committed
821 822 823
        case MAVLINK_MSG_ID_ACTION_ACK:
            mavlink_action_ack_t ack;
            mavlink_msg_action_ack_decode(&message, &ack);
824 825
            if (ack.result == 1)
            {
lm's avatar
lm committed
826
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed action: %1").arg(ack.action));
827 828 829
            }
            else
            {
lm's avatar
lm committed
830
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected action: %1").arg(ack.action));
831 832
            }
            break;
pixhawk's avatar
pixhawk committed
833
        case MAVLINK_MSG_ID_DEBUG:
834
            emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), "raw", mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow());
pixhawk's avatar
pixhawk committed
835
            break;
LM's avatar
LM committed
836
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
837
            {
LM's avatar
LM committed
838 839
                mavlink_roll_pitch_yaw_thrust_setpoint_t out;
                mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
840
                quint64 time = getUnixTime(out.time_us*1000);
LM's avatar
LM committed
841 842 843 844 845
                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);
LM's avatar
LM committed
846 847
            }
            break;
848 849
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
LM's avatar
LM committed
850 851
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
852 853
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
854 855
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
856
            }
LM's avatar
LM committed
857
            break;
pixhawk's avatar
pixhawk committed
858

859 860
        case MAVLINK_MSG_ID_WAYPOINT:
            {
LM's avatar
LM committed
861 862 863
                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;
864 865
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
866 867
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
868
            }
LM's avatar
LM committed
869
            break;
pixhawk's avatar
pixhawk committed
870

871 872
        case MAVLINK_MSG_ID_WAYPOINT_ACK:
            {
LM's avatar
LM committed
873 874
                mavlink_waypoint_ack_t wpa;
                mavlink_msg_waypoint_ack_decode(&message, &wpa);
875 876
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
877 878
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
879
            }
LM's avatar
LM committed
880
            break;
881

882 883
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
LM's avatar
LM committed
884 885
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
886 887
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
888 889
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
890
            }
LM's avatar
LM committed
891
            break;
pixhawk's avatar
pixhawk committed
892

893 894
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
            {
LM's avatar
LM committed
895 896 897 898 899 900 901 902
                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;
pixhawk's avatar
pixhawk committed
903

904 905
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
            {
LM's avatar
LM committed
906 907 908 909 910
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
911

912 913
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
914 915 916 917 918
                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;
919 920
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
            {
LM's avatar
LM committed
921 922 923 924 925 926 927 928 929 930 931 932 933
                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;
934 935 936 937 938 939 940 941 942 943

        case MAVLINK_MSG_ID_OPTICAL_FLOW:
            {
                mavlink_optical_flow_t flow;
                mavlink_msg_optical_flow_decode(&message, &flow);
                quint64 time = getUnixTime(flow.time);

                emit valueChanged(uasId, QString("opt_flow_%1.x").arg(flow.sensor_id), "Pixel", flow.flow_x, time);
                emit valueChanged(uasId, QString("opt_flow_%1.y").arg(flow.sensor_id), "Pixel", flow.flow_y, time);
                emit valueChanged(uasId, QString("opt_flow_%1.qual").arg(flow.sensor_id), "0-255", flow.quality, time);
pixhawk's avatar
pixhawk committed
944
                emit valueChanged(uasId, QString("opt_flow_%1.dist").arg(flow.sensor_id), "m", flow.ground_distance, time);
945 946
            }
            break;
947 948
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
949 950 951 952 953 954 955 956 957 958 959
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
                //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;
960
#ifdef MAVLINK_ENABLED_PIXHAWK
961 962
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
963 964 965 966 967 968 969 970 971 972 973
                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;
974

975 976
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
977 978 979 980 981 982 983 984 985 986 987
                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;
988 989
                }

990 991
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
992 993 994 995 996
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
997

LM's avatar
LM committed
998
                ++imagePacketsArrived;
999

LM's avatar
LM committed
1000 1001 1002 1003 1004 1005 1006 1007
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    imagePacketsArrived = 0;
                    emit imageReady(this);
                    qDebug() << "imageReady emitted. all packets arrived";
                }
1008
            }
LM's avatar
LM committed
1009
            break;
1010
#endif
1011
        case MAVLINK_MSG_ID_DEBUG_VECT:
1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086
        {
            mavlink_debug_vect_t vect;
            mavlink_msg_debug_vect_decode(&message, &vect);
            QString str((const char*)vect.name);
            quint64 time = getUnixTime(vect.usec);
            emit valueChanged(uasId, str+".x", "raw", vect.x, time);
            emit valueChanged(uasId, str+".y", "raw", vect.y, time);
            emit valueChanged(uasId, str+".z", "raw", vect.z, time);
        }
        break;
        // WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET
//        case MAVLINK_MSG_ID_MEMORY_VECT:
//        {
//            mavlink_memory_vect_t vect;
//            mavlink_msg_memory_vect_decode(&message, &vect);
//            QString str("mem_%1");
//            quint64 time = getUnixTime(0);
//            int16_t *mem0 = (int16_t *)&vect.value[0];
//            uint16_t *mem1 = (uint16_t *)&vect.value[0];
//            int32_t *mem2 = (int32_t *)&vect.value[0];
//            // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem
//            float *mem4 = (float *)&vect.value[0];
//            if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ;
//            if ( vect.ver == 1)
//            {
//                switch (vect.type) {
//                default:
//                case 0:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
//                    break;
//                case 1:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
//                    break;
//                case 2:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
//                    break;
//                case 3:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
//                    break;
//                case 4:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
//                    break;
//                case 5:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
//                    break;
//                case 6:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
//                    break;
//                }
//            }
//        }
//        break;
				//#ifdef MAVLINK_ENABLED_PIXHAWK
				//            case MAVLINK_MSG_ID_POINT_OF_INTEREST:
				//            {
				//                mavlink_point_of_interest_t poi;
				//                mavlink_msg_point_of_interest_decode(&message, &poi);
				//                emit poiFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN), poi.x, poi.y, poi.z);
				//            }
				//            break;
				//            case MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION:
				//            {
				//                mavlink_point_of_interest_connection_t poi;
				//                mavlink_msg_point_of_interest_connection_decode(&message, &poi);
				//                emit poiConnectionFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN), poi.x1, poi.y1, poi.z1, poi.x2, poi.y2, poi.z2);
				//            }
				//            break;
				//#endif
lm's avatar
lm committed
1087
#ifdef MAVLINK_ENABLED_UALBERTA
1088 1089
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
LM's avatar
LM committed
1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = getUnixTime();
                emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time);
                emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time);
                emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time);
                emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time);
                emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time);
                emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time);
            }
            break;
1101 1102
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
LM's avatar
LM committed
1103 1104
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
1105 1106 1107 1108 1109 1110
                QVector<uint16_t> aileron;
                QVector<uint16_t> elevator;
                QVector<uint16_t> rudder;
                QVector<uint16_t> gyro;
                QVector<uint16_t> pitch;
                QVector<uint16_t> throttle;
LM's avatar
LM committed
1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129

                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN; ++i)
                    aileron << radioMsg.aileron[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN; ++i)
                    elevator << radioMsg.elevator[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN; ++i)
                    rudder << radioMsg.rudder[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN; ++i)
                    gyro << radioMsg.gyro[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN; ++i)
                    pitch << radioMsg.pitch[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN; ++i)
                    throttle << radioMsg.throttle[i];

                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;
1130

1131
#endif
LM's avatar
LM committed
1132
            // Messages to ignore
1133
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
1134
            break;
1135 1136 1137 1138
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
1139 1140 1141 1142 1143 1144 1145
                    unknownPackets.append(message.msgid);
                    QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid);
                    GAudioOutput::instance()->say(errString+tr(", please check console for details."));
                    emit textMessageReceived(uasId, message.compid, 255, errString);
                    std::cout << "Unable to decode message from system " << std::dec << static_cast<int>(message.sysid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
                    //qDebug() << std::cerr << "Unable to decode message from system " << std::dec << static_cast<int>(message.acid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
                }
lm's avatar
lm committed
1146
            }
LM's avatar
LM committed
1147
            break;
pixhawk's avatar
pixhawk committed
1148 1149 1150 1151
        }
    }
}

1152 1153 1154 1155 1156 1157 1158 1159 1160
void UAS::setHomePosition(double lat, double lon, double alt)
{
    // Send new home position to UAS
    mavlink_gps_set_global_origin_t home;
    home.target_system = uasId;
    home.target_component = 0; // ALL components
    home.latitude = lat*1E7;
    home.longitude = lon*1E7;
    home.altitude = alt*1000;
1161
    qDebug() << "lat:" << home.latitude << " lon:" << home.longitude;
1162 1163 1164 1165 1166
    mavlink_message_t msg;
    mavlink_msg_gps_set_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
    sendMessage(msg);
}

1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181
void UAS::setLocalOriginAtCurrentGPSPosition()
{
    bool result = false;
    QMessageBox msgBox;
    msgBox.setIcon(QMessageBox::Warning);
    msgBox.setText("Setting new World Coordinate Frame Origin");
    msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location");
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();

    // Close the message box shortly after the click to prevent accidental clicks
    QTimer::singleShot(5000, &msgBox, SLOT(reject()));


1182 1183
    if (ret == QMessageBox::Yes)
    {
1184
        mavlink_message_t msg;
1185
        mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_ACTION_SET_ORIGIN);
1186 1187 1188 1189 1190 1191 1192 1193 1194 1195
        // Send message twice to increase chance that it reaches its goal
        sendMessage(msg);
        // Wait 5 ms
        MG::SLEEP::usleep(5000);
        // Send again
        sendMessage(msg);
        result = true;
    }
}

pixhawk's avatar
pixhawk committed
1196 1197
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1198
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1199
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1200 1201
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
1202
#else
lm's avatar
lm committed
1203 1204 1205 1206
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1207
#endif
pixhawk's avatar
pixhawk committed
1208 1209
}

pixhawk's avatar
pixhawk committed
1210 1211
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1212
#ifdef MAVLINK_ENABLED_PIXHAWK
1213 1214 1215
    mavlink_message_t msg;
    mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
    sendMessage(msg);
lm's avatar
lm committed
1216
#else
1217 1218 1219 1220
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1221 1222 1223 1224 1225
#endif
}

void UAS::startRadioControlCalibration()
{
1226 1227 1228
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_RC);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1229 1230
}

lm's avatar
lm committed
1231 1232
void UAS::startDataRecording()
{
1233 1234 1235
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_START);
    sendMessage(msg);
lm's avatar
lm committed
1236 1237 1238 1239
}

void UAS::pauseDataRecording()
{
1240 1241 1242
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_PAUSE);
    sendMessage(msg);
lm's avatar
lm committed
1243 1244 1245 1246
}

void UAS::stopDataRecording()
{
1247 1248 1249
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_STOP);
    sendMessage(msg);
lm's avatar
lm committed
1250 1251
}

pixhawk's avatar
pixhawk committed
1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272
void UAS::startMagnetometerCalibration()
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_MAG);
    sendMessage(msg);
}

void UAS::startGyroscopeCalibration()
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_GYRO);
    sendMessage(msg);
}

void UAS::startPressureCalibration()
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_PRESSURE);
    sendMessage(msg);
}

LM's avatar
LM committed
1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325
quint64 UAS::getUnixReferenceTime(quint64 time)
{
    // Same as getUnixTime, but does not react to attitudeStamped mode
    if (time == 0)
    {
        //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
        return QGC::groundTimeMilliseconds();
    }
    // Check if time is smaller than 40 years,
    // assuming no system without Unix timestamp
    // runs longer than 40 years continuously without
    // reboot. In worst case this will add/subtract the
    // communication delay between GCS and MAV,
    // it will never alter the timestamp in a safety
    // critical way.
    //
    // Calculation:
    // 40 years
    // 365 days
    // 24 hours
    // 60 minutes
    // 60 seconds
    // 1000 milliseconds
    // 1000 microseconds
#ifndef _MSC_VER
    else if (time < 1261440000000000LLU)
#else
        else if (time < 1261440000000000)
#endif
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
        if (onboardTimeOffset == 0)
        {
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
        }
        return time/1000 + onboardTimeOffset;
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
        return time/1000;
    }
}

/**
 * @warning If attitudeStamped is enabled, this function will not actually return the precise time stamp
 *          of this measurement augmented to UNIX time, but will MOVE the timestamp IN TIME to match
 *          the last measured attitude. There is no reason why one would want this, except for
 *          system setups where the onboard clock is not present or broken and datasets should
 *          be collected that are still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED
 *          RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
 */
1326 1327
quint64 UAS::getUnixTime(quint64 time)
{
LM's avatar
LM committed
1328 1329 1330 1331
    if (attitudeStamped)
    {
        return lastAttitude;
    }
1332 1333
    if (time == 0)
    {
LM's avatar
LM committed
1334
        //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
LM's avatar
LM committed
1335
        return QGC::groundTimeMilliseconds();
1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352
    }
    // Check if time is smaller than 40 years,
    // assuming no system without Unix timestamp
    // runs longer than 40 years continuously without
    // reboot. In worst case this will add/subtract the
    // communication delay between GCS and MAV,
    // it will never alter the timestamp in a safety
    // critical way.
    //
    // Calculation:
    // 40 years
    // 365 days
    // 24 hours
    // 60 minutes
    // 60 seconds
    // 1000 milliseconds
    // 1000 microseconds
1353
#ifndef _MSC_VER
1354
    else if (time < 1261440000000000LLU)
1355
#else
LM's avatar
LM committed
1356
        else if (time < 1261440000000000)
1357
#endif
LM's avatar
LM committed
1358 1359
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1360 1361
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1362
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1363
        }
1364
        return time/1000 + onboardTimeOffset;
1365 1366 1367
    }
    else
    {
1368 1369
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1370
        return time/1000;
1371 1372 1373
    }
}

1374 1375
QList<QString> UAS::getParameterNames(int component)
{
1376 1377
    if (parameters.contains(component))
    {
1378
        return parameters.value(component)->keys();
1379 1380 1381
    }
    else
    {
1382 1383 1384 1385 1386 1387 1388 1389 1390
        return QList<QString>();
    }
}

QList<int> UAS::getComponentIds()
{
    return parameters.keys();
}

pixhawk's avatar
pixhawk committed
1391
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1392
{
1393 1394
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
    {
1395
        //this->mode = mode; //no call assignament, update receive message from UAS
pixhawk's avatar
pixhawk committed
1396
        mavlink_message_t msg;
lm's avatar
lm committed
1397
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
1398
        sendMessage(msg);
lm's avatar
lm committed
1399
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
1400 1401 1402
    }
    else
    {
1403 1404
        qDebug() << "uas Mode not assign: " << mode;
    }
pixhawk's avatar
pixhawk committed
1405 1406 1407 1408 1409
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1410 1411 1412 1413
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1414
            sendMessage(link, message);
1415 1416 1417
        }
        else
        {
1418 1419 1420
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1421 1422 1423
    }
}

1424 1425 1426 1427
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1428

1429 1430 1431 1432
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1433
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1434 1435 1436 1437 1438 1439
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1440
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1441 1442
                        sendMessage(serial, message);
                    }
1443 1444 1445 1446 1447 1448
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1449 1450
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1451
    if(!link) return;
pixhawk's avatar
pixhawk committed
1452 1453 1454
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1455
    int len = mavlink_msg_to_send_buffer(buffer, &message);
1456
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
1457
    // If link is connected
1458 1459
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1460 1461 1462 1463 1464 1465 1466 1467
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1468
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1469
{
1470
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1471 1472
}

1473 1474
QString UAS::getNavModeText(int mode)
{
1475 1476
    switch (mode)
    {
1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508
    case MAV_NAV_GROUNDED:
        return QString("GROUNDED");
        break;
    case MAV_NAV_HOLD:
        return QString("HOLD");
        break;
    case MAV_NAV_LANDING:
        return QString("LANDING");
        break;
    case MAV_NAV_LIFTOFF:
        return QString("LIFTOFF");
        break;
    case MAV_NAV_LOITER:
        return QString("LOITER");
        break;
    case MAV_NAV_LOST:
        return QString("LOST");
        break;
    case MAV_NAV_RETURNING:
        return QString("RETURNING");
        break;
    case MAV_NAV_VECTOR:
        return QString("VECTOR");
        break;
    case MAV_NAV_WAYPOINT:
        return QString("WAYPOINT");
        break;
    default:
        return QString("UNKNOWN");
    }
}

pixhawk's avatar
pixhawk committed
1509 1510
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1511 1512
    switch (statusCode)
    {
lm's avatar
lm committed
1513
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1514
        uasState = tr("UNINIT");
1515
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1516
        break;
lm's avatar
lm committed
1517
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1518
        uasState = tr("BOOT");
1519
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1520
        break;
lm's avatar
lm committed
1521
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1522
        uasState = tr("CALIBRATING");
1523
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1524
        break;
lm's avatar
lm committed
1525
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1526
        uasState = tr("ACTIVE");
1527
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1528
        break;
lm's avatar
lm committed
1529 1530
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1531
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1532 1533
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1534
        uasState = tr("CRITICAL");
1535
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1536
        break;
lm's avatar
lm committed
1537
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1538
        uasState = tr("EMERGENCY");
1539
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1540
        break;
James Goppert's avatar
James Goppert committed
1541
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1542 1543 1544
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1545

lm's avatar
lm committed
1546
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1547
        uasState = tr("SHUTDOWN");
1548
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1549
        break;
1550

lm's avatar
lm committed
1551
    default:
pixhawk's avatar
pixhawk committed
1552
        uasState = tr("UNKNOWN");
1553
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1554 1555 1556 1557
        break;
    }
}

1558 1559
QImage UAS::getImage()
{
LM's avatar
LM committed
1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606
#ifdef MAVLINK_ENABLED_PIXHAWK

    qDebug() << "IMAGE TYPE:" << imageType;

    // RAW greyscale
    if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
    {
        // TODO FIXME Fabian
        // RAW hardcoded to 22x22
        int imgWidth = 22;
        int imgHeight = 22;
        int imgColors = 255;
        //const int headerSize = 15;

        // Construct PGM header
        QString header("P5\n%1 %2\n%3\n");
        header = header.arg(imgWidth).arg(imgHeight).arg(imgColors);

        QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size());
        tmpImage.append(imageRecBuffer);

        //qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header;

        if (imageRecBuffer.isNull())
        {
            qDebug()<< "could not convertToPGM()";
            return QImage();
        }

        if (!image.loadFromData(tmpImage, "PGM"))
        {
            qDebug()<< "could not create extracted image";
            return QImage();
        }

    }
    // BMP with header
    else if (imageType == MAVLINK_DATA_STREAM_IMG_BMP ||
             imageType == MAVLINK_DATA_STREAM_IMG_JPEG ||
             imageType == MAVLINK_DATA_STREAM_IMG_PGM ||
             imageType == MAVLINK_DATA_STREAM_IMG_PNG)
    {
       if (!image.loadFromData(imageRecBuffer))
        {
           qDebug() << "Loading data from image buffer failed!";
        }
    }
1607 1608
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1609
    //imageRecBuffer.clear();
1610
    return image;
1611 1612
#else
	return QImage();
LM's avatar
LM committed
1613
#endif
1614

1615 1616 1617 1618
}

void UAS::requestImage()
{
1619
#ifdef MAVLINK_ENABLED_PIXHAWK
1620 1621
    qDebug() << "trying to get an image from the uas...";

1622 1623 1624
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1625 1626 1627 1628
        mavlink_message_t msg;
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 50);
        sendMessage(msg);
    }
1629
#endif
1630
}
pixhawk's avatar
pixhawk committed
1631 1632 1633 1634 1635 1636 1637 1638 1639


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1640
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1641
{
1642 1643
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1644
        return 0;
1645 1646 1647
    }
    else
    {
pixhawk's avatar
pixhawk committed
1648 1649 1650 1651
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1652
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1653 1654 1655 1656
{
    return commStatus;
}

1657 1658 1659
void UAS::requestParameters()
{
    mavlink_message_t msg;
1660
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1661 1662
    // Send message twice to increase chance of reception
    sendMessage(msg);
1663 1664
}

1665
void UAS::writeParametersToStorage()
1666
{
1667 1668 1669
    mavlink_message_t msg;
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_STORAGE_WRITE);
unknown's avatar
unknown committed
1670
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1671 1672 1673 1674 1675 1676 1677 1678 1679
    sendMessage(msg);
}

void UAS::readParametersFromStorage()
{
    mavlink_message_t msg;
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(uint8_t)MAV_ACTION_STORAGE_READ);
    sendMessage(msg);
lm's avatar
lm committed
1680 1681
}

1682
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1683 1684
{
    // Buffers to write data to
1685
    mavlink_message_t msg;
1686
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1687 1688
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1689
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1690 1691
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1692 1693
    // TODO: use 0 to turn off and get rid of enable/disable? will require
    //  a different magic flag for turning on defaults, possibly something really high like 1111 ?
lm's avatar
lm committed
1694 1695
    stream.req_message_rate = 0;
    // Start / stop the message
1696
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1697 1698 1699 1700 1701
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
1702
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1703 1704
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1705 1706 1707
    sendMessage(msg);
}

1708
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1709 1710 1711
{
    // Buffers to write data to
    mavlink_message_t msg;
1712
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1713
    // Select the message to request from now on
1714
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1715
    // Select the update rate in Hz the message should be send
1716
    stream.req_message_rate = rate;
lm's avatar
lm committed
1717
    // Start / stop the message
1718
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1719 1720 1721 1722 1723
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
1724
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1725 1726
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1727 1728 1729
    sendMessage(msg);
}

1730
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1731
{
1732 1733 1734 1735
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1736
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1737
    // Select the update rate in Hz the message should be send
1738
    stream.req_message_rate = rate;
1739
    // Start / stop the message
1740
    stream.start_stop = (rate) ? 1 : 0;
1741 1742 1743 1744 1745 1746
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1747 1748
    // Send message twice to increase chance of reception
    sendMessage(msg);
1749
    sendMessage(msg);
lm's avatar
lm committed
1750
}
1751

1752
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1753
{
1754 1755 1756 1757 1758
#if defined(MAVLINK_ENABLED_UALBERTA_MESSAGES)
    mavlink_message_t msg;
    mavlink_msg_request_rc_channels_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, enabled);
    sendMessage(msg);
#else
1759 1760 1761
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1762
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1763
    // Select the update rate in Hz the message should be send
1764
    stream.req_message_rate = rate;
1765
    // Start / stop the message
1766
    stream.start_stop = (rate) ? 1 : 0;
1767 1768 1769 1770 1771 1772
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1773 1774
    // Send message twice to increase chance of reception
    sendMessage(msg);
1775
    sendMessage(msg);
1776
#endif
lm's avatar
lm committed
1777 1778
}

1779
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1780
{
1781 1782 1783 1784
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1785
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1786
    // Select the update rate in Hz the message should be send
1787
    stream.req_message_rate = rate;
1788
    // Start / stop the message
1789
    stream.start_stop = (rate) ? 1 : 0;
1790 1791 1792 1793 1794 1795
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1796 1797
    // Send message twice to increase chance of reception
    sendMessage(msg);
1798
    sendMessage(msg);
lm's avatar
lm committed
1799 1800
}

lm's avatar
lm committed
1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821
//void UAS::enableRawSensorFusionTransmission(int rate)
//{
//    // Buffers to write data to
//    mavlink_message_t msg;
//    mavlink_request_data_stream_t stream;
//    // Select the message to request from now on
//    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSOR_FUSION;
//    // Select the update rate in Hz the message should be send
//    stream.req_message_rate = rate;
//    // Start / stop the message
//    stream.start_stop = (rate) ? 1 : 0;
//    // The system which should take this command
//    stream.target_system = uasId;
//    // The component / subsystem which should take this command
//    stream.target_component = 0;
//    // Encode and send the message
//    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
//}
1822

1823
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1824 1825 1826 1827 1828
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1829
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1830
    // Select the update rate in Hz the message should be send
1831
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1832
    // Start / stop the message
1833
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

1845
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1846 1847 1848 1849 1850
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1851
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1852
    // Select the update rate in Hz the message should be send
1853
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1854
    // Start / stop the message
1855
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

1867
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1868 1869 1870 1871 1872
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1873
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1874
    // Select the update rate in Hz the message should be send
1875
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1876
    // Start / stop the message
1877
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

1889
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1890 1891 1892 1893 1894
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1895
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1896
    // Select the update rate in Hz the message should be send
1897
    stream.req_message_rate = rate;
1898
    // Start / stop the message
1899
    stream.start_stop = (rate) ? 1 : 0;
1900 1901 1902 1903 1904 1905
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1906 1907
    // Send message twice to increase chance of reception
    sendMessage(msg);
1908
    sendMessage(msg);
1909 1910
}

lm's avatar
lm committed
1911 1912 1913 1914 1915 1916 1917
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
lm's avatar
lm committed
1918 1919
void UAS::setParameter(const int component, const QString& id, const float value)
{
1920 1921
    if (!id.isNull())
    {
1922 1923 1924 1925 1926 1927 1928
        mavlink_message_t msg;
        mavlink_param_set_t p;
        p.param_value = value;
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

        // Copy string into buffer, ensuring not to exceed the buffer size
1929 1930
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1931
            // String characters
1932 1933
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1934 1935
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1936 1937 1938 1939 1940
            //        // Null termination at end of string or end of buffer
            //        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
            //        {
            //            p.param_id[i] = '\0';
            //        }
1941
            // Zero fill
1942 1943
            else
            {
1944 1945
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1946
        }
1947 1948
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1949
    }
1950 1951
}

1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962 1963
void UAS::requestParameter(int component, int parameter)
{
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
    read.param_index = parameter;
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << parameter;
}

1964 1965 1966 1967
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
1968 1969 1970 1971
    if (airframe == 0)
    {
        switch (systemType)
        {
1972 1973 1974 1975 1976 1977 1978 1979 1980 1981 1982
        case MAV_FIXED_WING:
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
        case MAV_QUADROTOR:
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1983 1984 1985
void UAS::setUASName(const QString& name)
{
    this->name = name;
1986
    writeSettings();
1987
    emit nameChanged(name);
1988
    emit systemSpecsChanged(uasId);
1989 1990
}

lm's avatar
lm committed
1991 1992 1993 1994
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
    mavlink_command_t cmd;
1995 1996 1997 1998 1999 2000 2001 2002 2003 2004 2005 2006 2007 2008 2009 2010 2011 2012 2013 2014 2015 2016 2017 2018 2019
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
    cmd.target_system = uasId;
    cmd.target_component = 0;
    mavlink_msg_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
    mavlink_command_t cmd;
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
    cmd.target_system = uasId;
    cmd.target_component = component;
    mavlink_msg_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
2020 2021 2022
    sendMessage(msg);
}

2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035
/**
 * Sets an action
 *
 **/
void UAS::setAction(MAV_ACTION action)
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, action);
    // Send message twice to increase chance that it reaches its goal
    sendMessage(msg);
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
2036
/**
lm's avatar
lm committed
2037
 * Launches the system
pixhawk's avatar
pixhawk committed
2038 2039 2040 2041
 *
 **/
void UAS::launch()
{
2042
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2043
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2044
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_TAKEOFF);
2045 2046 2047
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2048 2049 2050 2051 2052 2053 2054 2055
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
2056
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2057
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2058
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
2059 2060 2061
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2062 2063 2064 2065 2066 2067 2068 2069
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
2070
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2071
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2072
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
2073 2074 2075
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2076 2077 2078 2079 2080 2081 2082 2083 2084 2085 2086 2087 2088 2089
}

void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust)
{
    // Scale values
    double rollPitchScaling = 0.2f;
    double yawScaling = 0.5f;
    double thrustScaling = 1.0f;

    manualRollAngle = roll * rollPitchScaling;
    manualPitchAngle = pitch * rollPitchScaling;
    manualYawAngle = yaw * yawScaling;
    manualThrust = thrust * thrustScaling;

2090 2091
    if(mode == (int)MAV_MODE_MANUAL)
    {
2092 2093 2094 2095
        mavlink_message_t message;
        mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
        sendMessage(message);
        qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;
pixhawk's avatar
pixhawk committed
2096

2097
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
2098 2099 2100
    }
    else
    {
2101 2102
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2103 2104
}

2105 2106 2107 2108 2109
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2110 2111
void UAS::receiveButton(int buttonIndex)
{
2112 2113
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2114
    case 0:
pixhawk's avatar
pixhawk committed
2115

pixhawk's avatar
pixhawk committed
2116 2117
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2118

pixhawk's avatar
pixhawk committed
2119 2120 2121 2122 2123
        break;
    default:

        break;
    }
2124
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2125 2126 2127

}

2128

2129
/*void UAS::requestWaypoints()
2130 2131 2132 2133 2134
{
//    mavlink_message_t msg;
//    mavlink_msg_waypoint_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 25);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2135 2136
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
2137 2138
}

pixhawk's avatar
pixhawk committed
2139 2140
void UAS::setWaypoint(Waypoint* wp)
{
2141 2142 2143 2144 2145 2146 2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157 2158
//    mavlink_message_t msg;
//    mavlink_waypoint_set_t set;
//    set.id = wp->id;
//    //QString name = wp->name;
//    // FIXME Check if this works properly
//    //name.truncate(MAVLINK_MSG_WAYPOINT_SET_FIELD_NAME_LEN);
//    //strcpy((char*)set.name, name.toStdString().c_str());
//    set.autocontinue = wp->autocontinue;
//    set.target_component = 25; // FIXME
//    set.target_system = uasId;
//    set.active = wp->current;
//    set.x = wp->x;
//    set.y = wp->y;
//    set.z = wp->z;
//    set.yaw = wp->yaw;
//    mavlink_msg_waypoint_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &set);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2159 2160 2161 2162
}

void UAS::setWaypointActive(int id)
{
2163 2164 2165 2166 2167 2168 2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183 2184 2185
//    mavlink_message_t msg;
//    mavlink_waypoint_set_active_t active;
//    active.id = id;
//    active.target_system = uasId;
//    active.target_component = 25; // FIXME
//    mavlink_msg_waypoint_set_active_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &active);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
//    // TODO This should be not directly emitted, but rather being fed back from the UAS
//    emit waypointSelected(getUASID(), id);
}

void UAS::clearWaypointList()
{
//    mavlink_message_t msg;
//    // FIXME
//    mavlink_waypoint_clear_list_t clist;
//    clist.target_system = uasId;
//    clist.target_component = 25;  // FIXME
//    mavlink_msg_waypoint_clear_list_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &clist);
//    sendMessage(msg);
//    qDebug() << "UAS clears Waypoints!";
2186
}*/
pixhawk's avatar
pixhawk committed
2187 2188 2189 2190


void UAS::halt()
{
2191
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2192
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2193
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
2194 2195 2196
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2197 2198 2199 2200
}

void UAS::go()
{
2201
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2202
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2203
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
2204 2205 2206
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2207 2208 2209 2210 2211
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
2212
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2213
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2214
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
2215 2216 2217
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2218 2219 2220 2221 2222 2223 2224 2225
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2226
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2227
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2228
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
2229 2230 2231
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2232 2233 2234 2235 2236 2237 2238 2239 2240 2241 2242 2243 2244 2245 2246 2247 2248 2249 2250 2251 2252 2253 2254
}

/**
 * All systems are immediately shut down (e.g. the main power line is cut).
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
    bool result = false;
    QMessageBox msgBox;
    msgBox.setIcon(QMessageBox::Critical);
    msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS");
    msgBox.setInformativeText("Do you want to cut power on all systems?");
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();

    // Close the message box shortly after the click to prevent accidental clicks
    QTimer::singleShot(5000, &msgBox, SLOT(reject()));


2255 2256
    if (ret == QMessageBox::Yes)
    {
2257
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2258
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
2259
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
2260 2261 2262
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
2263 2264 2265 2266 2267
        result = true;
    }
    return result;
}

2268 2269
void UAS::startHil()
{
James Goppert's avatar
James Goppert committed
2270 2271 2272 2273 2274 2275
    mavlink_message_t msg;
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_START_HILSIM);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
2276 2277
}

2278 2279
void UAS::stopHil()
{
James Goppert's avatar
James Goppert committed
2280 2281 2282 2283 2284 2285
    mavlink_message_t msg;
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_STOP_HILSIM);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
2286 2287 2288
}


pixhawk's avatar
pixhawk committed
2289 2290 2291 2292 2293 2294 2295
void UAS::shutdown()
{
    bool result = false;
    QMessageBox msgBox;
    msgBox.setIcon(QMessageBox::Critical);
    msgBox.setText("Shutting down the UAS");
    msgBox.setInformativeText("Do you want to shut down the onboard computer?");
2296

pixhawk's avatar
pixhawk committed
2297 2298 2299 2300 2301 2302 2303
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();

    // Close the message box shortly after the click to prevent accidental clicks
    QTimer::singleShot(5000, &msgBox, SLOT(reject()));

2304 2305
    if (ret == QMessageBox::Yes)
    {
pixhawk's avatar
pixhawk committed
2306
        // If the active UAS is set, execute command
2307
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2308
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
2309
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
2310 2311 2312
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
2313

pixhawk's avatar
pixhawk committed
2314 2315 2316 2317
        result = true;
    }
}

2318 2319
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2320 2321 2322 2323 2324 2325
    mavlink_message_t msg;
    mavlink_msg_position_target_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, x, y, z, yaw);

    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
2326 2327
}

pixhawk's avatar
pixhawk committed
2328 2329 2330
/**
 * @return The name of this system as string in human-readable form
 */
2331
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2332 2333
{
    QString result;
2334 2335
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2336
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2337 2338 2339
    }
    else
    {
pixhawk's avatar
pixhawk committed
2340 2341 2342 2343 2344
        result = name;
    }
    return result;
}

2345 2346 2347 2348 2349 2350 2351 2352 2353 2354
const QString& UAS::getShortState() const
{
    return shortStateText;
}

const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2355 2356
void UAS::addLink(LinkInterface* link)
{
2357 2358
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2359
        links->append(link);
2360
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2361 2362 2363
    }
}

2364 2365 2366
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2367 2368
    if (link)
    {
2369 2370 2371 2372
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2373 2374 2375 2376 2377 2378 2379 2380 2381 2382 2383 2384 2385 2386 2387
/**
 * @brief Get the links associated with this robot
 *
 **/
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}



void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2388 2389
    switch (batteryType)
    {
lm's avatar
lm committed
2390
    case NICD:
pixhawk's avatar
pixhawk committed
2391
        break;
lm's avatar
lm committed
2392
    case NIMH:
pixhawk's avatar
pixhawk committed
2393
        break;
lm's avatar
lm committed
2394
    case LIION:
pixhawk's avatar
pixhawk committed
2395
        break;
lm's avatar
lm committed
2396
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2397 2398 2399
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2400
    case LIFE:
pixhawk's avatar
pixhawk committed
2401
        break;
lm's avatar
lm committed
2402
    case AGZN:
pixhawk's avatar
pixhawk committed
2403 2404 2405 2406
        break;
    }
}

2407 2408
void UAS::setBatterySpecs(const QString& specs)
{
2409 2410
    if (specs.length() == 0 || specs.contains("%"))
    {
2411
        batteryRemainingEstimateEnabled = false;
2412
        bool ok;
2413 2414 2415
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2416 2417
        if (ok)
        {
2418
            warnLevelPercent = temp;
2419 2420 2421
        }
        else
        {
2422 2423
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2424 2425 2426
    }
    else
    {
2427 2428 2429 2430 2431
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2432 2433
        if (parts.length() == 3)
        {
2434 2435 2436 2437 2438 2439 2440 2441 2442 2443 2444
            float temp;
            bool ok;
            // Get the empty voltage
            temp = parts.at(0).toFloat(&ok);
            if (ok) emptyVoltage = temp;
            // Get the warning voltage
            temp = parts.at(1).toFloat(&ok);
            if (ok) warnVoltage = temp;
            // Get the full voltage
            temp = parts.at(2).toFloat(&ok);
            if (ok) fullVoltage = temp;
2445 2446 2447
        }
        else
        {
2448 2449
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2450 2451 2452 2453 2454
    }
}

QString UAS::getBatterySpecs()
{
2455 2456
    if (batteryRemainingEstimateEnabled)
    {
2457
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2458 2459 2460
    }
    else
    {
2461 2462
        return QString("%1%").arg(warnLevelPercent);
    }
2463 2464
}

pixhawk's avatar
pixhawk committed
2465 2466 2467 2468 2469 2470 2471 2472 2473 2474 2475 2476 2477
int UAS::calculateTimeRemaining()
{
    quint64 dt = MG::TIME::getGroundTimeNow() - startTime;
    double seconds = dt / 1000.0f;
    double voltDifference = startVoltage - currentVoltage;
    if (voltDifference <= 0) voltDifference = 0.00000000001f;
    double dischargePerSecond = voltDifference / seconds;
    int remaining = static_cast<int>((currentVoltage - emptyVoltage) / dischargePerSecond);
    // Can never be below 0
    if (remaining < 0) remaining = 0;
    return remaining;
}

lm's avatar
lm committed
2478 2479 2480
/**
 * @return charge level in percent - 0 - 100
 */
2481
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2482
{
2483 2484 2485 2486
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2487
            chargeLevel = 0.0f;
2488 2489 2490
        }
        else if (lpVoltage > fullVoltage)
        {
2491
            chargeLevel = 100.0f;
2492 2493 2494
        }
        else
        {
2495 2496
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2497 2498
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2499 2500
}

lm's avatar
lm committed
2501 2502
void UAS::startLowBattAlarm()
{
2503 2504
    if (!lowBattAlarm)
    {
2505
        GAudioOutput::instance()->alert(tr("SYSTEM %1 HAS LOW BATTERY").arg(getUASName()));
2506
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2507 2508 2509 2510 2511 2512
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2513 2514
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2515 2516 2517 2518
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}