UAS.cc 88.6 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 31 32 33
#ifdef QGC_PROTOBUF_ENABLED
#include <google/protobuf/descriptor.h>
#endif

34
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lm's avatar
lm committed
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 77
    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(true),
    mode(-1),
    status(-1),
    navMode(-1),
    onboardTimeOffset(0),
    controlRollManual(true),
    controlPitchManual(true),
    controlYawManual(true),
    controlThrustManual(true),
    manualRollAngle(0),
    manualPitchAngle(0),
    manualYawAngle(0),
    manualThrust(0),
    receiveDropRate(0),
    sendDropRate(0),
    lowBattAlarm(false),
    positionLock(false),
    localX(0.0),
    localY(0.0),
    localZ(0.0),
    latitude(0.0),
    longitude(0.0),
    altitude(0.0),
    roll(0.0),
    pitch(0.0),
    yaw(0.0),
    statusTimeout(new QTimer(this)),
LM's avatar
LM committed
78
    #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
79 80 81 82
    receivedPointCloudTimestamp(0.0),
    receivedRGBDImageTimestamp(0.0),
    receivedObstacleListTimestamp(0.0),
    receivedPathTimestamp(0.0),
LM's avatar
LM committed
83
    #endif
lm's avatar
lm committed
84 85 86 87 88 89 90 91 92 93
    paramsOnceRequested(false),
    airframe(QGC_AIRFRAME_EASYSTAR),
    attitudeKnown(false),
    paramManager(NULL),
    attitudeStamped(false),
    lastAttitude(0),
    simulation(new QGCFlightGearLink(this)),
    isLocalPositionKnown(false),
    isGlobalPositionKnown(false),
    systemIsArmed(false)
pixhawk's avatar
pixhawk committed
94
{
95 96 97 98 99 100
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
    }

101
    color = UASInterface::getNextColor();
lm's avatar
lm committed
102
    setBatterySpecs(QString("9V,9.5V,12.6V"));
103
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
104
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
105
    statusTimeout->start(500);
106
    readSettings();
107 108 109 110

    // Initial signals
    emit disarmed();
    emit armingChanged(false);
pixhawk's avatar
pixhawk committed
111 112 113 114
}

UAS::~UAS()
{
115
    writeSettings();
pixhawk's avatar
pixhawk committed
116
    delete links;
117
    links=NULL;
pixhawk's avatar
pixhawk committed
118 119
}

120 121 122 123 124
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
125 126
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
127
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
128 129 130 131 132 133 134 135 136
    settings.endGroup();
    settings.sync();
}

void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
137 138
    this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
    this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
139
    if (settings.contains("BATTERY_SPECS")) {
140 141
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
142 143 144
    settings.endGroup();
}

145
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
146 147 148 149
{
    return uasId;
}

150 151
void UAS::updateState()
{
152 153
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
154 155
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
156 157 158 159
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

160 161
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
162 163
    if (positionLock)
    {
164
        positionLock = false;
165 166 167
    }
    else
    {
lm's avatar
lm committed
168
        if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock)
169
        {
170 171 172 173 174
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
175 176
void UAS::setSelected()
{
177 178
    if (UASManager::instance()->getActiveUAS() != this)
    {
179 180 181 182 183 184 185 186
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

bool UAS::getSelected() const
{
    return (UASManager::instance()->getActiveUAS() == this);
pixhawk's avatar
pixhawk committed
187 188 189 190
}

void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
191
    if (!link) return;
192 193
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
194
        addLink(link);
195
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
196 197
    }

LM's avatar
LM committed
198 199 200 201 202 203 204
    if (!components.contains(message.compid))
    {
        QString componentName;

        switch (message.compid)
        {
        case MAV_COMP_ID_ALL:
LM's avatar
LM committed
205 206 207 208
        {
            componentName = "ANONYMOUS";
            break;
        }
LM's avatar
LM committed
209
        case MAV_COMP_ID_IMU:
LM's avatar
LM committed
210 211 212 213
        {
            componentName = "IMU #1";
            break;
        }
LM's avatar
LM committed
214
        case MAV_COMP_ID_CAMERA:
LM's avatar
LM committed
215 216 217 218
        {
            componentName = "CAMERA";
            break;
        }
LM's avatar
LM committed
219
        case MAV_COMP_ID_MISSIONPLANNER:
LM's avatar
LM committed
220 221 222 223
        {
            componentName = "MISSIONPLANNER";
            break;
        }
LM's avatar
LM committed
224 225 226 227 228 229
        }

        components.insert(message.compid, componentName);
        emit componentCreated(uasId, message.compid, componentName);
    }

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

LM's avatar
LM committed
232 233 234 235
    // 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))
236
    {
pixhawk's avatar
pixhawk committed
237 238
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
239

240 241 242
        bool multiComponentSourceDetected = false;
        bool wrongComponent = false;

243 244 245 246 247 248 249 250 251 252 253
        switch (message.compid)
        {
        case MAV_COMP_ID_IMU_2:
            // Prefer IMU 2 over IMU 1 (FIXME)
            componentID[message.msgid] = MAV_COMP_ID_IMU_2;
            break;
        default:
            // Do nothing
            break;
        }

254 255 256
        // Store component ID
        if (componentID[message.msgid] == -1)
        {
257
            // Prefer the first component
258 259 260 261 262 263 264 265 266 267 268 269 270 271 272
            componentID[message.msgid] = message.compid;
        }
        else
        {
            // Got this message already
            if (componentID[message.msgid] != message.compid)
            {
                componentMulti[message.msgid] = true;
                wrongComponent = true;
            }
        }

        if (componentMulti[message.msgid] == true) multiComponentSourceDetected = true;


273 274
        switch (message.msgid)
        {
pixhawk's avatar
pixhawk committed
275
        case MAVLINK_MSG_ID_HEARTBEAT:
276
        {
LM's avatar
LM committed
277 278 279 280
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
281
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
282
            emit heartbeat(this);
283 284
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
285 286 287 288 289
			
			// Send the base_mode and system_status values to the plotter. This uses the ground time
			// so the Ground Time checkbox must be ticked for these values to display
            quint64 time = getUnixTime();
			QString name = QString("M%1:HEARTBEAT.%2").arg(message.sysid);
290 291 292
			emit valueChanged(uasId, name.arg("base_mode"), "bits", state.base_mode, time);
			emit valueChanged(uasId, name.arg("custom_mode"), "bits", state.custom_mode, time);
			emit valueChanged(uasId, name.arg("system_status"), "-", state.system_status, time);
293
			
pixhawk's avatar
pixhawk committed
294
            // Set new type if it has changed
295
            if (this->type != state.type)
296
            {
297
                this->type = state.type;
298 299 300 301
                if (airframe == 0)
                {
                    switch (type)
                    {
lm's avatar
lm committed
302
                    case MAV_TYPE_FIXED_WING:
303 304
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
lm's avatar
lm committed
305
                    case MAV_TYPE_QUADROTOR:
306 307
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
308 309 310
                    case MAV_TYPE_HEXAROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
                        break;
311 312 313 314 315
                    default:
                        // Do nothing
                        break;
                    }
                }
316
                this->autopilot = state.autopilot;
pixhawk's avatar
pixhawk committed
317 318
                emit systemTypeSet(this, type);
            }
319

320 321 322 323 324 325 326 327 328 329 330 331 332 333 334
            bool currentlyArmed = state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;

            if (systemIsArmed != currentlyArmed)
            {
                systemIsArmed = currentlyArmed;
                emit armingChanged(systemIsArmed);
                if (systemIsArmed)
                {
                    emit armed();
                }
                else
                {
                    emit disarmed();
                }
            }
335

336 337 338 339 340 341
            QString audiostring = "System " + getUASName();
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
342 343


344 345 346 347 348 349 350
            if (state.system_status != this->status)
            {
                statechanged = true;
                this->status = state.system_status;
                getStatusForCode((int)state.system_status, uasState, stateDescription);
                emit statusChanged(this, uasState, stateDescription);
                emit statusChanged(this->status);
351

352
                shortStateText = uasState;
353

354 355
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
356

357
            if (this->mode != static_cast<int>(state.base_mode))
358 359
            {
                modechanged = true;
360
                this->mode = static_cast<int>(state.base_mode);
361
                shortModeText = getShortModeTextFor(this->mode);
362

363
                emit modeChanged(this->getUASID(), shortModeText, "");
LM's avatar
LM committed
364

365 366
                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed
367

368
            if (navMode != state.custom_mode)
369
            {
370 371
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
LM's avatar
LM committed
372
                //navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
373
            }
374

375 376 377 378 379 380 381 382 383 384 385
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
386

387 388 389 390 391 392 393
            if ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY)
            {
                GAudioOutput::instance()->startEmergency();
            }
            else if (modechanged || statechanged)
            {
                GAudioOutput::instance()->stopEmergency();
394
                GAudioOutput::instance()->say(audiostring.toLower());
395
            }
LM's avatar
LM committed
396
        }
397

398 399 400
            break;
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
LM's avatar
LM committed
401 402 403 404 405 406
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_sys_status_t state;
            mavlink_msg_sys_status_decode(&message, &state);
407

408 409 410 411 412 413 414 415 416 417 418 419
			// Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
            quint64 time = getUnixTime();
			QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid);
			emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time);
			emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time);
			emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time);
			emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time);
			emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time);
			emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time);
			emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);

			// Process CPU load.
LM's avatar
LM committed
420
            emit loadChanged(this,state.load/10.0f);
421
			emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
LM's avatar
LM committed
422

423
			// Battery charge/time remaining/voltage calculations
LM's avatar
LM committed
424 425
            currentVoltage = state.voltage_battery/1000.0f;
            lpVoltage = filterVoltage(currentVoltage);
LM's avatar
LM committed
426

LM's avatar
LM committed
427 428 429 430 431 432 433
            if (startVoltage == 0) startVoltage = currentVoltage;
            timeRemaining = calculateTimeRemaining();
            if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
            {
                chargeLevel = state.battery_remaining;
            }
            emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
434 435 436 437 438 439 440 441 442
			emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time);
            emit voltageChanged(message.sysid, currentVoltage);
			emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time);

			// And if the battery current draw is measured, log that also.
			if (state.current_battery != -1)
			{
				emit valueChanged(uasId, name.arg("battery_current"), "A", ((double)state.current_battery) / 100.0f, time);
			}
443

LM's avatar
LM committed
444 445 446 447
            // LOW BATTERY ALARM
            if (lpVoltage < warnVoltage)
            {
                startLowBattAlarm();
448
            }
LM's avatar
LM committed
449
            else
LM's avatar
LM committed
450
            {
LM's avatar
LM committed
451
                stopLowBattAlarm();
pixhawk's avatar
pixhawk committed
452
            }
453

454 455 456 457 458 459 460 461

            // control_sensors_enabled:
            // relevant bits: 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control
            emit attitudeControlEnabled(state.onboard_control_sensors_enabled & (1 << 11));
            emit positionYawControlEnabled(state.onboard_control_sensors_enabled & (1 << 12));
            emit positionZControlEnabled(state.onboard_control_sensors_enabled & (1 << 13));
            emit positionXYControlEnabled(state.onboard_control_sensors_enabled & (1 << 14));

462 463 464 465 466 467
			// Trigger drop rate updates as needed. Here we convert the incoming
			// drop_rate_comm value from 1/100 of a percent in a uint16 to a true
			// percentage as a float. We also cap the incoming value at 100% as defined
			// by the MAVLink specifications.
			if (state.drop_rate_comm > 10000)
			{
468
				state.drop_rate_comm = 10000;
469
			}
470 471
			emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f);
			emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time);
472
		}
LM's avatar
LM committed
473
            break;
pixhawk's avatar
pixhawk committed
474
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
475 476 477 478
        {
            mavlink_attitude_t attitude;
            mavlink_msg_attitude_decode(&message, &attitude);
            quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509

            emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time);

            if (!wrongComponent)
            {
                lastAttitude = time;
                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);

                //                // Emit in angles

                //                // Convert yaw angle to compass value
                //                // in 0 - 360 deg range
                //                float compass = (yaw/M_PI)*180.0+360.0f;
                //                if (compass > -10000 && compass < 10000)
                //                {
                //                    while (compass > 360.0f) {
                //                        compass -= 360.0f;
                //                    }
                //                }
                //                else
                //                {
                //                    // Set to 0, since it is an invalid value
                //                    compass = 0.0f;
                //                }

                attitudeKnown = true;
                emit attitudeChanged(this, roll, pitch, yaw, time);
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
            }
LM's avatar
LM committed
510
        }
LM's avatar
LM committed
511
            break;
lm's avatar
lm committed
512
        case MAVLINK_MSG_ID_HIL_CONTROLS:
LM's avatar
LM committed
513 514 515 516 517
        {
            mavlink_hil_controls_t hil;
            mavlink_msg_hil_controls_decode(&message, &hil);
            emit hilControlsChanged(hil.time_usec, hil.roll_ailerons, hil.pitch_elevator, hil.yaw_rudder, hil.throttle, hil.mode, hil.nav_mode);
        }
lm's avatar
lm committed
518
            break;
519
        case MAVLINK_MSG_ID_VFR_HUD:
LM's avatar
LM committed
520 521 522 523 524 525
        {
            mavlink_vfr_hud_t hud;
            mavlink_msg_vfr_hud_decode(&message, &hud);
            quint64 time = getUnixTime();
            // Display updated values
            emit thrustChanged(this, hud.throttle/100.0);
lm's avatar
lm committed
526

LM's avatar
LM committed
527 528 529 530
            if (!attitudeKnown)
            {
                yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
531
            }
LM's avatar
LM committed
532 533 534 535

            emit altitudeChanged(uasId, hud.alt);
            emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
        }
LM's avatar
LM committed
536
            break;
lm's avatar
lm committed
537
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
lm's avatar
lm committed
538
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
539
            //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
540 541 542 543
        {
            mavlink_local_position_ned_t pos;
            mavlink_msg_local_position_ned_decode(&message, &pos);
            quint64 time = getUnixTime(pos.time_boot_ms);
LM's avatar
LM committed
544

LM's avatar
LM committed
545 546
            // Emit position always with component ID
            emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time);
547

LM's avatar
LM committed
548

LM's avatar
LM committed
549 550 551 552 553
            if (!wrongComponent)
            {
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
554

LM's avatar
LM committed
555
                // Emit
556

LM's avatar
LM committed
557 558
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
559

LM's avatar
LM committed
560 561 562 563
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
LM's avatar
LM committed
564
                }
LM's avatar
LM committed
565 566
                positionLock = true;
                isLocalPositionKnown = true;
567
            }
LM's avatar
LM committed
568
        }
569 570
            break;
        case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
LM's avatar
LM committed
571 572 573 574 575 576 577
        {
            mavlink_global_vision_position_estimate_t pos;
            mavlink_msg_global_vision_position_estimate_decode(&message, &pos);
            quint64 time = getUnixTime(pos.usec);
            emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time);
            emit attitudeChanged(this, message.compid, pos.roll, pos.pitch, pos.yaw, time);
        }
LM's avatar
LM committed
578
            break;
579
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
580 581
            //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
582 583 584 585 586 587 588 589 590 591 592 593
        {
            mavlink_global_position_int_t pos;
            mavlink_msg_global_position_int_decode(&message, &pos);
            quint64 time = getUnixTime();
            latitude = pos.lat/(double)1E7;
            longitude = pos.lon/(double)1E7;
            altitude = pos.alt/1000.0;
            speedX = pos.vx/100.0;
            speedY = pos.vy/100.0;
            speedZ = pos.vz/100.0;
            emit globalPositionChanged(this, latitude, longitude, altitude, time);
            emit speedChanged(this, speedX, speedY, speedZ, time);
594

LM's avatar
LM committed
595 596
            // Set internal state
            if (!positionLock)
LM's avatar
LM committed
597
            {
LM's avatar
LM committed
598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615
                // If position was not locked before, notify positive
                GAudioOutput::instance()->notifyPositive();
            }
            positionLock = true;
            isGlobalPositionKnown = true;
            //TODO fix this hack for forwarding of global position for patch antenna tracking
            forwardMessage(message);
        }
            break;
        case MAVLINK_MSG_ID_GPS_RAW_INT:
        {
            mavlink_gps_raw_int_t pos;
            mavlink_msg_gps_raw_int_decode(&message, &pos);

            // SANITY CHECK
            // only accept values in a realistic range
            // quint64 time = getUnixTime(pos.time_usec);
            quint64 time = getUnixTime(pos.time_usec);
616 617 618 619 620 621 622 623 624
            
            emit gpsLocalizationChanged(this, pos.fix_type);
            // TODO: track localization state not only for gps but also for other loc. sources
            int loc_type = pos.fix_type;
            if (loc_type == 1)
            {
                loc_type = 0; 
            }
            emit localizationChanged(this, loc_type);
LM's avatar
LM committed
625 626

            if (pos.fix_type > 2)
LM's avatar
LM committed
627
            {
LM's avatar
LM committed
628
                emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
LM's avatar
LM committed
629 630 631 632
                latitude = pos.lat/(double)1E7;
                longitude = pos.lon/(double)1E7;
                altitude = pos.alt/1000.0;
                positionLock = true;
633
                isGlobalPositionKnown = true;
LM's avatar
LM committed
634

LM's avatar
LM committed
635 636 637
                // Check for NaN
                int alt = pos.alt;
                if (!isnan(alt) && !isinf(alt))
638
                {
LM's avatar
LM committed
639 640 641 642 643
                    alt = 0;
                    //emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE");
                }
                // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
                // Smaller than threshold and not NaN
LM's avatar
LM committed
644

LM's avatar
LM committed
645
                float vel = pos.vel/100.0f;
LM's avatar
LM committed
646

LM's avatar
LM committed
647 648 649 650 651 652 653 654 655
                if (vel < 1000000 && !isnan(vel) && !isinf(vel))
                {
                    // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time);
                    //qDebug() << "GOT GPS RAW";
                    // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                }
                else
                {
                    emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
lm's avatar
lm committed
656 657
                }
            }
LM's avatar
LM committed
658
        }
LM's avatar
LM committed
659
            break;
660
        case MAVLINK_MSG_ID_GPS_STATUS:
LM's avatar
LM committed
661 662 663 664
        {
            mavlink_gps_status_t pos;
            mavlink_msg_gps_status_decode(&message, &pos);
            for(int i = 0; i < (int)pos.satellites_visible; i++)
665
            {
LM's avatar
LM committed
666
                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]));
667
            }
LM's avatar
LM committed
668
        }
LM's avatar
LM committed
669
            break;
670
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
LM's avatar
LM committed
671 672 673 674 675
        {
            mavlink_gps_global_origin_t pos;
            mavlink_msg_gps_global_origin_decode(&message, &pos);
            emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
        }
LM's avatar
LM committed
676
            break;
677
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
LM's avatar
LM committed
678 679 680 681 682 683 684 685 686 687 688 689 690
        {
            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);
        }
LM's avatar
LM committed
691
            break;
692
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
LM's avatar
LM committed
693 694 695 696 697 698 699 700 701 702 703 704 705
        {
            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
706
            break;
707
        case MAVLINK_MSG_ID_PARAM_VALUE:
LM's avatar
LM committed
708 709 710 711 712 713 714 715 716 717 718 719
        {
            mavlink_param_value_t value;
            mavlink_msg_param_value_decode(&message, &value);
            QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
            QString parameterName = QString(bytes);
            int component = message.compid;
            mavlink_param_union_t val;
            val.param_float = value.param_value;
            val.type = value.param_type;

            // Insert component if necessary
            if (!parameters.contains(component))
720
            {
LM's avatar
LM committed
721 722
                parameters.insert(component, new QMap<QString, QVariant>());
            }
723

LM's avatar
LM committed
724 725
            // Insert parameter into registry
            if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
726

LM's avatar
LM committed
727 728 729 730 731 732 733 734 735 736 737 738
            // Insert with correct type
            switch (value.param_type)
            {
            case MAVLINK_TYPE_FLOAT:
            {
                // Variant
                QVariant param(val.param_float);
                parameters.value(component)->insert(parameterName, param);
                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, param);
                emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                qDebug() << "RECEIVED PARAM:" << param;
LM's avatar
LM committed
739
            }
LM's avatar
LM committed
740 741 742 743 744 745 746 747 748 749
                break;
            case MAVLINK_TYPE_UINT32_T:
            {
                // Variant
                QVariant param(val.param_uint32);
                parameters.value(component)->insert(parameterName, param);
                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, param);
                emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                qDebug() << "RECEIVED PARAM:" << param;
LM's avatar
LM committed
750
            }
LM's avatar
LM committed
751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766
                break;
            case MAVLINK_TYPE_INT32_T:
            {
                // Variant
                QVariant param(val.param_int32);
                parameters.value(component)->insert(parameterName, param);
                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, param);
                emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                qDebug() << "RECEIVED PARAM:" << param;
            }
                break;
            default:
                qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
            }
        }
LM's avatar
LM committed
767
            break;
768 769 770
        case MAVLINK_MSG_ID_COMMAND_ACK:
            mavlink_command_ack_t ack;
            mavlink_msg_command_ack_decode(&message, &ack);
771 772
            if (ack.result == 1)
            {
773
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
774 775 776
            }
            else
            {
777
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
778 779
            }
            break;
LM's avatar
LM committed
780
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
LM's avatar
LM committed
781 782 783 784 785 786
        {
            mavlink_roll_pitch_yaw_thrust_setpoint_t out;
            mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
            quint64 time = getUnixTimeFromMs(out.time_boot_ms);
            emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
        }
LM's avatar
LM committed
787
            break;
lm's avatar
lm committed
788
        case MAVLINK_MSG_ID_MISSION_COUNT:
LM's avatar
LM committed
789 790 791 792
        {
            mavlink_mission_count_t wpc;
            mavlink_msg_mission_count_decode(&message, &wpc);
            if (wpc.target_system == mavlink->getSystemId())
793
            {
LM's avatar
LM committed
794
                waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
pixhawk's avatar
pixhawk committed
795
            }
LM's avatar
LM committed
796 797 798 799 800
            else
            {
                qDebug() << "Got waypoint message, but was not for me";
            }
        }
LM's avatar
LM committed
801
            break;
pixhawk's avatar
pixhawk committed
802

lm's avatar
lm committed
803
        case MAVLINK_MSG_ID_MISSION_ITEM:
LM's avatar
LM committed
804 805 806 807 808
        {
            mavlink_mission_item_t wp;
            mavlink_msg_mission_item_decode(&message, &wp);
            //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
            if(wp.target_system == mavlink->getSystemId())
809
            {
LM's avatar
LM committed
810 811 812 813 814
                waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
            }
            else
            {
                qDebug() << "Got waypoint message, but was not for me";
815
            }
LM's avatar
LM committed
816
        }
LM's avatar
LM committed
817
            break;
pixhawk's avatar
pixhawk committed
818

lm's avatar
lm committed
819
        case MAVLINK_MSG_ID_MISSION_ACK:
LM's avatar
LM committed
820 821 822 823
        {
            mavlink_mission_ack_t wpa;
            mavlink_msg_mission_ack_decode(&message, &wpa);
            if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
824
            {
LM's avatar
LM committed
825
                waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
826
            }
LM's avatar
LM committed
827
        }
LM's avatar
LM committed
828
            break;
829

lm's avatar
lm committed
830
        case MAVLINK_MSG_ID_MISSION_REQUEST:
LM's avatar
LM committed
831 832 833 834
        {
            mavlink_mission_request_t wpr;
            mavlink_msg_mission_request_decode(&message, &wpr);
            if(wpr.target_system == mavlink->getSystemId())
835
            {
LM's avatar
LM committed
836
                waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
pixhawk's avatar
pixhawk committed
837
            }
LM's avatar
LM committed
838 839 840
            else
            {
                qDebug() << "Got waypoint message, but was not for me";
pixhawk's avatar
pixhawk committed
841
            }
LM's avatar
LM committed
842
        }
LM's avatar
LM committed
843
            break;
pixhawk's avatar
pixhawk committed
844

lm's avatar
lm committed
845
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
LM's avatar
LM committed
846 847 848 849 850 851 852 853
        {
            mavlink_mission_item_reached_t wpr;
            mavlink_msg_mission_item_reached_decode(&message, &wpr);
            waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
            QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq);
            GAudioOutput::instance()->say(text);
            emit textMessageReceived(message.sysid, message.compid, 0, text);
        }
LM's avatar
LM committed
854
            break;
pixhawk's avatar
pixhawk committed
855

lm's avatar
lm committed
856
        case MAVLINK_MSG_ID_MISSION_CURRENT:
LM's avatar
LM committed
857 858 859 860 861
        {
            mavlink_mission_current_t wpc;
            mavlink_msg_mission_current_decode(&message, &wpc);
            waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
        }
LM's avatar
LM committed
862
            break;
pixhawk's avatar
pixhawk committed
863

864
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
LM's avatar
LM committed
865
        {
866
            if (multiComponentSourceDetected && wrongComponent)
867
            {
868
                break;
LM's avatar
LM committed
869
            }
LM's avatar
LM committed
870 871 872 873
            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());
        }
LM's avatar
LM committed
874
            break;
875
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
LM's avatar
LM committed
876 877 878 879 880
        {
            mavlink_set_local_position_setpoint_t p;
            mavlink_msg_set_local_position_setpoint_decode(&message, &p);
            emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw);
        }
881
            break;
882
        case MAVLINK_MSG_ID_STATUSTEXT:
LM's avatar
LM committed
883 884 885 886 887 888 889 890 891 892 893
        {
            QByteArray b;
            b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
            mavlink_msg_statustext_get_text(&message, 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);
        }
LM's avatar
LM committed
894
            break;
895
#ifdef MAVLINK_ENABLED_PIXHAWK
896
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
LM's avatar
LM committed
897 898 899 900 901 902 903 904 905 906 907 908 909
        {
            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;
            imageWidth = p.width;
            imageHeight = p.height;
            imageStart = QGC::groundTimeMilliseconds();
        }
LM's avatar
LM committed
910
            break;
911

912
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
LM's avatar
LM committed
913 914 915 916 917
        {
            mavlink_encapsulated_data_t img;
            mavlink_msg_encapsulated_data_decode(&message, &img);
            int seq = img.seqnr;
            int pos = seq * imagePayload;
LM's avatar
LM committed
918

LM's avatar
LM committed
919 920 921 922 923 924 925
            // Check if we have a valid transaction
            if (imagePackets == 0)
            {
                // NO VALID TRANSACTION - ABORT
                // Restart statemachine
                imagePacketsArrived = 0;
            }
926

LM's avatar
LM committed
927 928 929 930
            for (int i = 0; i < imagePayload; ++i)
            {
                if (pos <= imageSize) {
                    imageRecBuffer[pos] = img.data[i];
LM's avatar
LM committed
931
                }
LM's avatar
LM committed
932 933
                ++pos;
            }
934

LM's avatar
LM committed
935
            ++imagePacketsArrived;
936

LM's avatar
LM committed
937 938 939 940 941 942 943
            // emit signal if all packets arrived
            if ((imagePacketsArrived >= imagePackets))
            {
                // Restart statemachine
                imagePacketsArrived = 0;
                emit imageReady(this);
                qDebug() << "imageReady emitted. all packets arrived";
944
            }
LM's avatar
LM committed
945
        }
LM's avatar
LM committed
946
            break;
947
#endif
LM's avatar
LM committed
948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004
            //        case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT:
            //        {
            //            mavlink_object_detection_event_t event;
            //            mavlink_msg_object_detection_event_decode(&message, &event);
            //            QString str(event.name);
            //            emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance);
            //        }
            //        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++)
            //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
            //                    break;
            //                case 1:
            //                    for (int i = 0; i < 16; i++)
            //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
            //                    break;
            //                case 2:
            //                    for (int i = 0; i < 16; i++)
            //                        // FIXME REMOVE LATER 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++)
            //                        // FIXME REMOVE LATER 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++)
            //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
            //                    break;
            //                case 5:
            //                    for (int i = 0; i < 8; i++)
            //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
            //                    break;
            //                case 6:
            //                    for (int i = 0; i < 8; i++)
            //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
            //                    break;
            //                }
            //            }
            //        }
            //        break;
lm's avatar
lm committed
1005
#ifdef MAVLINK_ENABLED_UALBERTA
1006
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
LM's avatar
LM committed
1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017
        {
            mavlink_nav_filter_bias_t bias;
            mavlink_msg_nav_filter_bias_decode(&message, &bias);
            quint64 time = getUnixTime();
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time);
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time);
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time);
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time);
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time);
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time);
        }
LM's avatar
LM committed
1018
            break;
1019
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
LM's avatar
LM committed
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
        {
            mavlink_radio_calibration_t radioMsg;
            mavlink_msg_radio_calibration_decode(&message, &radioMsg);
            QVector<uint16_t> aileron;
            QVector<uint16_t> elevator;
            QVector<uint16_t> rudder;
            QVector<uint16_t> gyro;
            QVector<uint16_t> pitch;
            QVector<uint16_t> throttle;

            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;
        }
LM's avatar
LM committed
1047
            break;
1048

1049
#endif
LM's avatar
LM committed
1050
            // Messages to ignore
lm's avatar
lm committed
1051 1052 1053 1054 1055 1056 1057 1058
        case MAVLINK_MSG_ID_RAW_IMU:
        case MAVLINK_MSG_ID_SCALED_IMU:
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
        case MAVLINK_MSG_ID_RAW_PRESSURE:
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
        case MAVLINK_MSG_ID_OPTICAL_FLOW:
        case MAVLINK_MSG_ID_DEBUG_VECT:
LM's avatar
LM committed
1059
        case MAVLINK_MSG_ID_DEBUG:
1060 1061
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
1062
            break;
1063
        default:
LM's avatar
LM committed
1064 1065
        {
            if (!unknownPackets.contains(message.msgid))
1066
            {
LM's avatar
LM committed
1067 1068 1069 1070 1071 1072
                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
1073
            }
LM's avatar
LM committed
1074
        }
LM's avatar
LM committed
1075
            break;
pixhawk's avatar
pixhawk committed
1076 1077 1078 1079
        }
    }
}

1080
#if defined(QGC_PROTOBUF_ENABLED)
1081 1082
void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message)
{
LM's avatar
LM committed
1083 1084 1085 1086
    if (!link)
    {
        return;
    }
1087 1088 1089 1090 1091
    if (!links->contains(link))
    {
        addLink(link);
    }

1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126
    const google::protobuf::Descriptor* descriptor = message->GetDescriptor();
    if (!descriptor)
    {
        return;
    }

    const google::protobuf::FieldDescriptor* headerField = descriptor->FindFieldByName("header");
    if (!headerField)
    {
        return;
    }

    const google::protobuf::Descriptor* headerDescriptor = headerField->message_type();
    if (!headerDescriptor)
    {
        return;
    }

    const google::protobuf::FieldDescriptor* sourceSysIdField = headerDescriptor->FindFieldByName("source_sysid");
    if (!sourceSysIdField)
    {
        return;
    }

    const google::protobuf::Reflection* reflection = message->GetReflection();
    const google::protobuf::Message& headerMsg = reflection->GetMessage(*message, headerField);
    const google::protobuf::Reflection* headerReflection = headerMsg.GetReflection();

    int source_sysid = headerReflection->GetInt32(headerMsg, sourceSysIdField);

    if (source_sysid != uasId)
    {
        return;
    }

1127
#ifdef QGC_USE_PIXHAWK_MESSAGES
1128 1129
    if (message->GetTypeName() == pointCloud.GetTypeName())
    {
1130
        receivedPointCloudTimestamp = QGC::groundTimeSeconds();
1131
        pointCloudMutex.lock();
1132
        pointCloud.CopyFrom(*message);
1133
        pointCloudMutex.unlock();
1134
        emit pointCloudChanged(this);
1135
    }
1136 1137
    else if (message->GetTypeName() == rgbdImage.GetTypeName())
    {
1138
        receivedRGBDImageTimestamp = QGC::groundTimeSeconds();
1139
        rgbdImageMutex.lock();
1140
        rgbdImage.CopyFrom(*message);
1141
        rgbdImageMutex.unlock();
1142
        emit rgbdImageChanged(this);
1143
    }
1144 1145
    else if (message->GetTypeName() == obstacleList.GetTypeName())
    {
1146
        receivedObstacleListTimestamp = QGC::groundTimeSeconds();
1147
        obstacleListMutex.lock();
1148
        obstacleList.CopyFrom(*message);
1149
        obstacleListMutex.unlock();
1150 1151
        emit obstacleListChanged(this);
    }
1152 1153
    else if (message->GetTypeName() == path.GetTypeName())
    {
1154
        receivedPathTimestamp = QGC::groundTimeSeconds();
1155
        pathMutex.lock();
1156
        path.CopyFrom(*message);
1157
        pathMutex.unlock();
1158 1159
        emit pathChanged(this);
    }
1160
#endif
1161 1162 1163 1164
}

#endif

1165 1166
void UAS::setHomePosition(double lat, double lon, double alt)
{
1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195
    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()));


    if (ret == QMessageBox::Yes)
    {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 0, 0, 0, 0, lat, lon, alt);
        // Send message twice to increase chance that it reaches its goal
        sendMessage(msg);

        // Send new home position to UAS
        mavlink_set_gps_global_origin_t home;
        home.target_system = uasId;
        home.latitude = lat*1E7;
        home.longitude = lon*1E7;
        home.altitude = alt*1000;
        qDebug() << "lat:" << home.latitude << " lon:" << home.longitude;
        mavlink_msg_set_gps_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
        sendMessage(msg);
    }
1196 1197
}

1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211
void UAS::setLocalOriginAtCurrentGPSPosition()
{
    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()));


1212 1213
    if (ret == QMessageBox::Yes)
    {
1214 1215 1216 1217
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 1, 0, 0, 0, 0, 0, 0);
        // Send message twice to increase chance that it reaches its goal
        sendMessage(msg);
1218 1219 1220
    }
}

pixhawk's avatar
pixhawk committed
1221 1222
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1223
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1224
    mavlink_message_t msg;
LM's avatar
LM committed
1225
    mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw/M_PI*180.0);
pixhawk's avatar
pixhawk committed
1226
    sendMessage(msg);
1227
#else
lm's avatar
lm committed
1228 1229 1230 1231
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1232
#endif
pixhawk's avatar
pixhawk committed
1233 1234
}

pixhawk's avatar
pixhawk committed
1235 1236
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1237
#ifdef MAVLINK_ENABLED_PIXHAWK
1238
    mavlink_message_t msg;
1239
    mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
1240
    sendMessage(msg);
lm's avatar
lm committed
1241
#else
1242 1243 1244 1245
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1246 1247 1248 1249
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1250
{
1251 1252
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1253
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1, 0, 0, 0);
1254
    sendMessage(msg);
lm's avatar
lm committed
1255 1256
}

1257
void UAS::startDataRecording()
lm's avatar
lm committed
1258
{
1259
    mavlink_message_t msg;
1260
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2, 0, 0, 0);
1261
    sendMessage(msg);
lm's avatar
lm committed
1262 1263 1264 1265
}

void UAS::stopDataRecording()
{
1266
    mavlink_message_t msg;
1267
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0, 0, 0, 0);
1268
    sendMessage(msg);
lm's avatar
lm committed
1269 1270
}

pixhawk's avatar
pixhawk committed
1271 1272
void UAS::startMagnetometerCalibration()
{
1273 1274
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1275
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0, 0, 0, 0);
1276
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1277 1278 1279 1280
}

void UAS::startGyroscopeCalibration()
{
1281 1282
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1283
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0, 0, 0, 0);
1284
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1285 1286 1287 1288
}

void UAS::startPressureCalibration()
{
1289 1290
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1291
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0, 0, 0, 0);
1292
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1293 1294
}

LM's avatar
LM committed
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
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
LM's avatar
LM committed
1322
    else if (time < 1261440000000000)
LM's avatar
LM committed
1323
#endif
LM's avatar
LM committed
1324
    {
LM's avatar
LM committed
1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339
        //        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;
    }
}

1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352
/**
 * @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!
 */
quint64 UAS::getUnixTimeFromMs(quint64 time)
{
    return getUnixTime(time*1000);
}

LM's avatar
LM committed
1353 1354 1355 1356 1357 1358 1359 1360
/**
 * @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!
 */
1361 1362
quint64 UAS::getUnixTime(quint64 time)
{
1363
    quint64 ret = 0;
LM's avatar
LM committed
1364 1365
    if (attitudeStamped)
    {
1366
        ret = lastAttitude;
LM's avatar
LM committed
1367
    }
1368 1369
    if (time == 0)
    {
1370
        ret = QGC::groundTimeMilliseconds();
1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387
    }
    // 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
1388
#ifndef _MSC_VER
1389
    else if (time < 1261440000000000LLU)
1390
#else
LM's avatar
LM committed
1391
    else if (time < 1261440000000000)
1392
#endif
LM's avatar
LM committed
1393
    {
LM's avatar
LM committed
1394
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1395 1396
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1397
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1398
        }
1399
        ret = time/1000 + onboardTimeOffset;
1400 1401 1402
    }
    else
    {
1403 1404
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1405
        ret = time/1000;
1406
    }
1407
    return ret;
1408 1409
}

1410 1411
QList<QString> UAS::getParameterNames(int component)
{
1412 1413
    if (parameters.contains(component))
    {
1414
        return parameters.value(component)->keys();
1415 1416 1417
    }
    else
    {
1418 1419 1420 1421 1422 1423 1424 1425 1426
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1427
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1428
{
LM's avatar
LM committed
1429 1430 1431 1432 1433
    //this->mode = mode; //no call assignament, update receive message from UAS
    mavlink_message_t msg;
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode, (uint16_t)navMode);
    sendMessage(msg);
    qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
1434 1435 1436 1437 1438
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1439 1440 1441 1442
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1443
            sendMessage(link, message);
1444 1445 1446
        }
        else
        {
1447 1448 1449
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1450 1451 1452
    }
}

1453 1454 1455 1456
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1457

1458 1459 1460 1461
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1462
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1463 1464 1465 1466 1467 1468
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1469
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1470 1471
                        sendMessage(serial, message);
                    }
1472 1473 1474 1475 1476 1477
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1478 1479
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1480
    if(!link) return;
pixhawk's avatar
pixhawk committed
1481 1482 1483
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1484
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1485 1486
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
pixhawk's avatar
pixhawk committed
1487
    // If link is connected
1488 1489
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1490 1491 1492 1493 1494 1495 1496 1497
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1498
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1499
{
1500
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1501 1502
}

1503 1504
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1505 1506
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
LM's avatar
LM committed
1507 1508 1509 1510 1511 1512 1513 1514
        switch (mode)
        {
        case 0:
            return QString("PREFLIGHT");
            break;
        default:
            return QString("UNKNOWN");
        }
lm's avatar
lm committed
1515 1516 1517 1518 1519 1520 1521 1522 1523
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1524 1525
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1526 1527
}

pixhawk's avatar
pixhawk committed
1528 1529
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1530 1531
    switch (statusCode)
    {
lm's avatar
lm committed
1532
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1533
        uasState = tr("UNINIT");
1534
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1535
        break;
lm's avatar
lm committed
1536
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1537
        uasState = tr("BOOT");
1538
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1539
        break;
lm's avatar
lm committed
1540
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1541
        uasState = tr("CALIBRATING");
1542
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1543
        break;
lm's avatar
lm committed
1544
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1545
        uasState = tr("ACTIVE");
1546
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1547
        break;
lm's avatar
lm committed
1548 1549
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1550
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1551 1552
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1553
        uasState = tr("CRITICAL");
1554
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1555
        break;
lm's avatar
lm committed
1556
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1557
        uasState = tr("EMERGENCY");
1558
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1559
        break;
James Goppert's avatar
James Goppert committed
1560
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1561 1562 1563
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1564

lm's avatar
lm committed
1565
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1566
        uasState = tr("SHUTDOWN");
1567
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1568
        break;
1569

lm's avatar
lm committed
1570
    default:
pixhawk's avatar
pixhawk committed
1571
        uasState = tr("UNKNOWN");
1572
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1573 1574 1575 1576
        break;
    }
}

1577 1578
QImage UAS::getImage()
{
LM's avatar
LM committed
1579 1580 1581 1582 1583 1584 1585
#ifdef MAVLINK_ENABLED_PIXHAWK

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

    // RAW greyscale
    if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
    {
LM's avatar
LM committed
1586 1587
        // TODO FIXME
        int imgColors = 255;//imageSize/(imageWidth*imageHeight);
LM's avatar
LM committed
1588 1589 1590 1591
        //const int headerSize = 15;

        // Construct PGM header
        QString header("P5\n%1 %2\n%3\n");
LM's avatar
LM committed
1592
        header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
LM's avatar
LM committed
1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617

        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)
    {
LM's avatar
LM committed
1618
        if (!image.loadFromData(imageRecBuffer))
LM's avatar
LM committed
1619
        {
LM's avatar
LM committed
1620
            qDebug() << "Loading data from image buffer failed!";
LM's avatar
LM committed
1621 1622
        }
    }
1623 1624
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1625
    //imageRecBuffer.clear();
1626
    return image;
1627
#else
LM's avatar
LM committed
1628
    return QImage();
LM's avatar
LM committed
1629
#endif
1630

1631 1632 1633 1634
}

void UAS::requestImage()
{
1635
#ifdef MAVLINK_ENABLED_PIXHAWK
1636 1637
    qDebug() << "trying to get an image from the uas...";

1638 1639 1640
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1641
        mavlink_message_t msg;
LM's avatar
LM committed
1642
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50);
1643 1644
        sendMessage(msg);
    }
1645
#endif
1646
}
pixhawk's avatar
pixhawk committed
1647 1648 1649 1650 1651 1652 1653 1654 1655


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1656
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1657
{
1658 1659
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1660
        return 0;
1661 1662 1663
    }
    else
    {
LM's avatar
LM committed
1664
        return QGC::groundTimeMilliseconds() - startTime;
pixhawk's avatar
pixhawk committed
1665 1666 1667
    }
}

1668
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1669 1670 1671 1672
{
    return commStatus;
}

1673 1674 1675
void UAS::requestParameters()
{
    mavlink_message_t msg;
LM's avatar
LM committed
1676
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
1677
    sendMessage(msg);
1678 1679
}

1680
void UAS::writeParametersToStorage()
1681
{
1682
    mavlink_message_t msg;
1683
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
pixhawk's avatar
pixhawk committed
1684
    qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
1685
    sendMessage(msg);
1686 1687 1688 1689
}

void UAS::readParametersFromStorage()
{
1690
    mavlink_message_t msg;
1691
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
1692
    sendMessage(msg);
lm's avatar
lm committed
1693 1694
}

1695
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1696 1697
{
    // Buffers to write data to
1698
    mavlink_message_t msg;
1699
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1700 1701
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1702
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1703 1704
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1705 1706
    // 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
1707 1708
    stream.req_message_rate = 0;
    // Start / stop the message
1709
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1710 1711 1712 1713 1714
    // 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
1715
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1716 1717
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1718 1719
}

1720
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1721 1722 1723
{
    // Buffers to write data to
    mavlink_message_t msg;
1724
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1725
    // Select the message to request from now on
1726
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1727
    // Select the update rate in Hz the message should be send
1728
    stream.req_message_rate = rate;
lm's avatar
lm committed
1729
    // Start / stop the message
1730
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1731 1732 1733 1734 1735
    // 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
1736
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1737 1738
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1739 1740
}

1741
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1742
{
1743 1744 1745 1746
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1747
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1748
    // Select the update rate in Hz the message should be send
1749
    stream.req_message_rate = rate;
1750
    // Start / stop the message
1751
    stream.start_stop = (rate) ? 1 : 0;
1752 1753 1754 1755 1756 1757
    // 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);
1758 1759
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1760
}
1761

1762
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1763
{
1764 1765 1766 1767 1768
#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
1769 1770 1771
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1772
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1773
    // Select the update rate in Hz the message should be send
1774
    stream.req_message_rate = rate;
1775
    // Start / stop the message
1776
    stream.start_stop = (rate) ? 1 : 0;
1777 1778 1779 1780 1781 1782
    // 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);
1783 1784
    // Send message twice to increase chance of reception
    sendMessage(msg);
1785
#endif
lm's avatar
lm committed
1786 1787
}

1788
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1789
{
1790 1791 1792 1793
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1794
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1795
    // Select the update rate in Hz the message should be send
1796
    stream.req_message_rate = rate;
1797
    // Start / stop the message
1798
    stream.start_stop = (rate) ? 1 : 0;
1799 1800 1801 1802 1803 1804
    // 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);
1805 1806
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1807 1808
}

lm's avatar
lm committed
1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829
//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);
//}
1830

1831
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1832 1833 1834 1835 1836
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1837
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1838
    // Select the update rate in Hz the message should be send
1839
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1840
    // Start / stop the message
1841
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1842 1843 1844 1845 1846 1847 1848 1849 1850 1851
    // 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);
}

1852
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1853 1854 1855 1856 1857
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1858
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1859
    // Select the update rate in Hz the message should be send
1860
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1861
    // Start / stop the message
1862
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873
    // 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);
}

1874
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1875 1876 1877 1878 1879
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1880
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1881
    // Select the update rate in Hz the message should be send
1882
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1883
    // Start / stop the message
1884
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895
    // 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);
}

1896
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1897 1898 1899 1900 1901
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1902
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1903
    // Select the update rate in Hz the message should be send
1904
    stream.req_message_rate = rate;
1905
    // Start / stop the message
1906
    stream.start_stop = (rate) ? 1 : 0;
1907 1908 1909 1910 1911 1912
    // 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);
1913 1914
    // Send message twice to increase chance of reception
    sendMessage(msg);
1915
    sendMessage(msg);
1916 1917
}

lm's avatar
lm committed
1918 1919 1920 1921 1922 1923 1924
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1925
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
lm's avatar
lm committed
1926
{
1927 1928
    if (!id.isNull())
    {
1929 1930
        mavlink_message_t msg;
        mavlink_param_set_t p;
1931 1932 1933 1934 1935 1936 1937
        mavlink_param_union_t union_value;

        // Assign correct value based on QVariant
        switch (value.type())
        {
        case QVariant::Int:
            union_value.param_int32 = value.toInt();
1938
            p.param_type = MAVLINK_TYPE_INT32_T;
1939 1940 1941
            break;
        case QVariant::UInt:
            union_value.param_uint32 = value.toUInt();
1942
            p.param_type = MAVLINK_TYPE_UINT32_T;
1943 1944 1945
            break;
        case QMetaType::Float:
            union_value.param_float = value.toFloat();
1946
            p.param_type = MAVLINK_TYPE_FLOAT;
1947 1948 1949 1950 1951 1952 1953
            break;
        default:
            qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
            return;
        }

        p.param_value = union_value.param_float;
1954 1955 1956
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

1957 1958
        qDebug() << "SENT PARAM:" << value;

1959
        // Copy string into buffer, ensuring not to exceed the buffer size
1960 1961
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1962
            // String characters
1963 1964
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1965 1966
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1967 1968 1969 1970 1971
            //        // 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';
            //        }
1972
            // Zero fill
1973 1974
            else
            {
1975 1976
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1977
        }
1978 1979
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1980
    }
1981 1982
}

1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996
void UAS::requestParameter(int component, int id)
{
    // Request parameter, use parameter name to request it
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
    read.param_index = id;
    read.param_id[0] = '\0'; // Enforce null termination
    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" << id;
}

1997
void UAS::requestParameter(int component, const QString& parameter)
1998
{
1999
    // Request parameter, use parameter name to request it
2000 2001
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
2002 2003 2004 2005 2006 2007 2008 2009
    read.param_index = -1;
    // Copy full param name or maximum max field size
    if (parameter.length() > MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)
    {
        emit textMessageReceived(uasId, 0, 255, QString("QGC WARNING: Parameter name %1 is more than %2 bytes long. This might lead to errors and mishaps!").arg(parameter).arg(MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN-1));
    }
    memcpy(read.param_id, parameter.toStdString().c_str(), qMax(parameter.length(), MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN));
    read.param_id[15] = '\0'; // Enforce null termination
2010 2011 2012 2013
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
2014
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
2015 2016
}

2017 2018 2019 2020
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
2021 2022 2023 2024
    if (airframe == 0)
    {
        switch (systemType)
        {
lm's avatar
lm committed
2025
        case MAV_TYPE_FIXED_WING:
2026 2027
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
lm's avatar
lm committed
2028
        case MAV_TYPE_QUADROTOR:
2029 2030 2031 2032 2033 2034 2035
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

2036 2037
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
2038 2039 2040 2041 2042 2043 2044
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
2045 2046
}

lm's avatar
lm committed
2047 2048 2049
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
2050
    mavlink_command_long_t cmd;
2051 2052 2053 2054 2055 2056
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
2057 2058 2059
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
2060 2061
    cmd.target_system = uasId;
    cmd.target_component = 0;
2062
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
2063 2064 2065
    sendMessage(msg);
}

2066 2067 2068 2069
void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component)
{
    mavlink_message_t msg;
    mavlink_command_long_t cmd;
2070 2071 2072 2073 2074 2075
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
2076 2077 2078
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
2079 2080
    cmd.target_system = uasId;
    cmd.target_component = component;
2081
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
2082 2083 2084
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
2085
/**
lm's avatar
lm committed
2086
 * Launches the system
pixhawk's avatar
pixhawk committed
2087 2088 2089 2090
 *
 **/
void UAS::launch()
{
2091
    mavlink_message_t msg;
2092
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_NAV_TAKEOFF, 1, 0, 0, 0, 0, 0, 0, 0);
2093
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2094 2095 2096 2097 2098 2099
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
2100
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
2101
{
2102
    mavlink_message_t msg;
2103
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
2104
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2105 2106 2107 2108 2109 2110
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
2111
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
2112
{
2113
    mavlink_message_t msg;
2114
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
2115
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2116 2117 2118 2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129
}

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;

LM's avatar
LM committed
2130 2131
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
2132
    {
2133 2134 2135 2136
        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
2137

LM's avatar
LM committed
2138
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
2139 2140 2141
    }
    else
    {
2142 2143
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2144 2145
}

2146 2147 2148 2149 2150
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2151 2152
void UAS::receiveButton(int buttonIndex)
{
2153 2154
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2155
    case 0:
pixhawk's avatar
pixhawk committed
2156

pixhawk's avatar
pixhawk committed
2157 2158
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2159

pixhawk's avatar
pixhawk committed
2160 2161 2162 2163 2164
        break;
    default:

        break;
    }
2165
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2166 2167 2168

}

2169

pixhawk's avatar
pixhawk committed
2170 2171
void UAS::halt()
{
2172 2173 2174
    mavlink_message_t msg;
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_HOLD, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2175 2176 2177 2178
}

void UAS::go()
{
2179 2180 2181
    mavlink_message_t msg;
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2182 2183 2184 2185 2186
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
2187 2188 2189 2190 2191 2192 2193 2194 2195
    mavlink_message_t msg;

    double latitude = UASManager::instance()->getHomeLatitude();
    double longitude = UASManager::instance()->getHomeLongitude();
    double altitude = UASManager::instance()->getHomeAltitude();
    int frame = UASManager::instance()->getHomeFrame();

    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, frame, 0, latitude, longitude, altitude);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2196 2197 2198 2199 2200 2201 2202 2203
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2204 2205
    // FIXME MAVLINKV10PORTINGNEEDED
    halt();
pixhawk's avatar
pixhawk committed
2206 2207 2208
}

/**
lm's avatar
lm committed
2209
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2210 2211 2212 2213 2214 2215
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
2216
    halt();
lm's avatar
lm committed
2217
    // FIXME MAVLINKV10PORTINGNEEDED
LM's avatar
LM committed
2218 2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230 2231 2232 2233 2234 2235 2236 2237 2238 2239 2240 2241
    //    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()));


    //    if (ret == QMessageBox::Yes)
    //    {
    //        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_EMCY_KILL);
    //        // Send message twice to increase chance of reception
    //        sendMessage(msg);
    //        sendMessage(msg);
    //        result = true;
    //    }
    //    return result;
lm's avatar
lm committed
2242
    return false;
pixhawk's avatar
pixhawk committed
2243 2244
}

lm's avatar
lm committed
2245 2246 2247 2248 2249
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2250
        startHil();
lm's avatar
lm committed
2251 2252 2253
    }
    else
    {
2254
        stopHil();
lm's avatar
lm committed
2255 2256 2257 2258 2259 2260 2261 2262 2263 2264 2265 2266 2267 2268 2269 2270 2271 2272 2273 2274 2275 2276
    }
}

/**
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
*/
void UAS::sendHilState(uint64_t time_us, float roll, float pitch, float yaw, float rollspeed,
LM's avatar
LM committed
2277 2278
                       float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt,
                       int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
lm's avatar
lm committed
2279 2280 2281 2282 2283 2284 2285
{
    mavlink_message_t msg;
    mavlink_msg_hil_state_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, time_us, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc);
    sendMessage(msg);
}


2286 2287
void UAS::startHil()
{
lm's avatar
lm committed
2288 2289
    // Connect Flight Gear Link
    simulation->connectSimulation();
2290
    mavlink_message_t msg;
LM's avatar
LM committed
2291
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
2292
    sendMessage(msg);
2293 2294
}

2295 2296
void UAS::stopHil()
{
lm's avatar
lm committed
2297
    simulation->disconnectSimulation();
2298
    mavlink_message_t msg;
LM's avatar
LM committed
2299
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
2300
    sendMessage(msg);
2301 2302 2303
}


pixhawk's avatar
pixhawk committed
2304 2305
void UAS::shutdown()
{
2306 2307 2308 2309 2310
    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?");
lm's avatar
lm committed
2311

2312 2313 2314
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2315

2316 2317
    // Close the message box shortly after the click to prevent accidental clicks
    QTimer::singleShot(5000, &msgBox, SLOT(reject()));
lm's avatar
lm committed
2318

2319 2320 2321 2322
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2323
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 0, 2, 0, 0, 0, 0, 0);
2324 2325 2326
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2327 2328
}

2329 2330
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2331
    mavlink_message_t msg;
2332 2333 2334
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 1, 0, 0, yaw, x, y, z);
    sendMessage(msg);
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 0, 1, 0, yaw, x, y, z);
2335
    sendMessage(msg);
2336 2337
}

pixhawk's avatar
pixhawk committed
2338 2339 2340
/**
 * @return The name of this system as string in human-readable form
 */
2341
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2342 2343
{
    QString result;
2344 2345
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2346
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2347 2348 2349
    }
    else
    {
pixhawk's avatar
pixhawk committed
2350 2351 2352 2353 2354
        result = name;
    }
    return result;
}

2355 2356 2357 2358 2359
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2360 2361 2362
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2363 2364 2365
    uint8_t modeid = id;

    qDebug() << "MODE:" << modeid;
2366

LM's avatar
LM committed
2367
    // BASE MODE DECODING
pixhawk's avatar
pixhawk committed
2368
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
LM's avatar
LM committed
2369
    {
pixhawk's avatar
pixhawk committed
2370
        mode += "AUTO";
LM's avatar
LM committed
2371
    }
pixhawk's avatar
pixhawk committed
2372
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
LM's avatar
LM committed
2373
    {
LM's avatar
LM committed
2374
        mode += "|GUID";
LM's avatar
LM committed
2375
    }
pixhawk's avatar
pixhawk committed
2376
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
LM's avatar
LM committed
2377
    {
LM's avatar
LM committed
2378
        mode += "|STAB";
LM's avatar
LM committed
2379
    }
pixhawk's avatar
pixhawk committed
2380
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
LM's avatar
LM committed
2381
    {
LM's avatar
LM committed
2382
        mode += "|TEST";
LM's avatar
LM committed
2383
    }
pixhawk's avatar
pixhawk committed
2384
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
LM's avatar
LM committed
2385
    {
LM's avatar
LM committed
2386
        mode += "|MAN";
LM's avatar
LM committed
2387
    }
pixhawk's avatar
pixhawk committed
2388 2389

    if (modeid == 0)
LM's avatar
LM committed
2390
    {
2391
        mode = "PREFLIGHT";
LM's avatar
LM committed
2392 2393 2394
    }

    // ARMED STATE DECODING
pixhawk's avatar
pixhawk committed
2395
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
LM's avatar
LM committed
2396
    {
LM's avatar
LM committed
2397
        mode.prepend("A/");
LM's avatar
LM committed
2398 2399 2400
    }
    else
    {
LM's avatar
LM committed
2401
        mode.prepend("D/");
LM's avatar
LM committed
2402 2403 2404
    }

    // HARDWARE IN THE LOOP DECODING
pixhawk's avatar
pixhawk committed
2405
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
LM's avatar
LM committed
2406 2407
    {
        mode.prepend("HIL:");
2408 2409 2410 2411 2412
    }

    return mode;
}

2413 2414 2415 2416 2417
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2418 2419
void UAS::addLink(LinkInterface* link)
{
2420 2421
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2422
        links->append(link);
2423
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2424 2425 2426
    }
}

2427 2428 2429
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2430 2431
    if (link)
    {
2432 2433 2434 2435
        links->removeAt(links->indexOf(link));
    }
}

LM's avatar
LM committed
2436

pixhawk's avatar
pixhawk committed
2437 2438 2439 2440 2441
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}

LM's avatar
LM committed
2442 2443 2444 2445 2446
QMap<int, QString> UAS::getComponents()
{
    return components;
}

pixhawk's avatar
pixhawk committed
2447 2448 2449 2450 2451 2452


void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2453 2454
    switch (batteryType)
    {
lm's avatar
lm committed
2455
    case NICD:
pixhawk's avatar
pixhawk committed
2456
        break;
lm's avatar
lm committed
2457
    case NIMH:
pixhawk's avatar
pixhawk committed
2458
        break;
lm's avatar
lm committed
2459
    case LIION:
pixhawk's avatar
pixhawk committed
2460
        break;
lm's avatar
lm committed
2461
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2462 2463 2464
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2465
    case LIFE:
pixhawk's avatar
pixhawk committed
2466
        break;
lm's avatar
lm committed
2467
    case AGZN:
pixhawk's avatar
pixhawk committed
2468 2469 2470 2471
        break;
    }
}

2472 2473
void UAS::setBatterySpecs(const QString& specs)
{
2474 2475
    if (specs.length() == 0 || specs.contains("%"))
    {
2476
        batteryRemainingEstimateEnabled = false;
2477
        bool ok;
2478 2479 2480
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2481 2482
        if (ok)
        {
2483
            warnLevelPercent = temp;
2484 2485 2486
        }
        else
        {
2487 2488
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2489 2490 2491
    }
    else
    {
2492 2493 2494 2495 2496
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2497 2498
        if (parts.length() == 3)
        {
2499 2500 2501 2502 2503 2504 2505 2506 2507 2508 2509
            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;
2510 2511 2512
        }
        else
        {
2513 2514
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2515 2516 2517 2518 2519
    }
}

QString UAS::getBatterySpecs()
{
2520 2521
    if (batteryRemainingEstimateEnabled)
    {
2522
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2523 2524 2525
    }
    else
    {
2526 2527
        return QString("%1%").arg(warnLevelPercent);
    }
2528 2529
}

pixhawk's avatar
pixhawk committed
2530 2531
int UAS::calculateTimeRemaining()
{
LM's avatar
LM committed
2532
    quint64 dt = QGC::groundTimeMilliseconds() - startTime;
pixhawk's avatar
pixhawk committed
2533 2534 2535 2536 2537 2538 2539 2540 2541 2542
    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
2543 2544 2545
/**
 * @return charge level in percent - 0 - 100
 */
2546
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2547
{
2548 2549 2550 2551
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2552
            chargeLevel = 0.0f;
2553 2554 2555
        }
        else if (lpVoltage > fullVoltage)
        {
2556
            chargeLevel = 100.0f;
2557 2558 2559
        }
        else
        {
2560 2561
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2562 2563
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2564 2565
}

lm's avatar
lm committed
2566 2567
void UAS::startLowBattAlarm()
{
2568 2569
    if (!lowBattAlarm)
    {
2570
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2571
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2572 2573 2574 2575 2576 2577
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2578 2579
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2580 2581 2582 2583
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}