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

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

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

30
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lm's avatar
lm committed
31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83
    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)),
    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
84
{
85 86 87 88 89 90
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
    }

91
    color = UASInterface::getNextColor();
lm's avatar
lm committed
92
    setBatterySpecs(QString("9V,9.5V,12.6V"));
93
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
94
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
95
    statusTimeout->start(500);
96
    readSettings();
97 98 99 100

    // Initial signals
    emit disarmed();
    emit armingChanged(false);
pixhawk's avatar
pixhawk committed
101 102 103 104
}

UAS::~UAS()
{
105
    writeSettings();
pixhawk's avatar
pixhawk committed
106
    delete links;
107
    links=NULL;
pixhawk's avatar
pixhawk committed
108 109
}

110 111 112 113 114
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
115 116
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
117
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
118 119 120 121 122 123 124 125 126
    settings.endGroup();
    settings.sync();
}

void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
127 128
    this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
    this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
129
    if (settings.contains("BATTERY_SPECS")) {
130 131
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
132 133 134
    settings.endGroup();
}

135
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
136 137 138 139
{
    return uasId;
}

140 141
void UAS::updateState()
{
142 143
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
144 145
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
146 147 148 149
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

150 151
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
152 153
    if (positionLock)
    {
154
        positionLock = false;
155 156 157
    }
    else
    {
lm's avatar
lm committed
158
        if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock)
159
        {
160 161 162 163 164
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
165 166
void UAS::setSelected()
{
167
    if (UASManager::instance()->getActiveUAS() != this) {
168 169 170 171 172 173 174 175
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

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

178 179
void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
180 181
    if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
    {
pixhawk's avatar
pixhawk committed
182 183
        mavlink_named_value_float_t val;
        mavlink_msg_named_value_float_decode(&message, &val);
lm's avatar
lm committed
184 185
        QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
        emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
186 187 188
    }
    else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
    {
pixhawk's avatar
pixhawk committed
189 190
        mavlink_named_value_int_t val;
        mavlink_msg_named_value_int_decode(&message, &val);
lm's avatar
lm committed
191 192
        QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN);
        emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
193 194 195
    }
}

pixhawk's avatar
pixhawk committed
196 197
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
198
    if (!link) return;
199 200
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
201
        addLink(link);
202
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
203
    }
204 205 206 207
    //    else
    //    {
    //        qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
    //    }
pixhawk's avatar
pixhawk committed
208

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

LM's avatar
LM committed
211 212 213 214
    // 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))
215
    {
pixhawk's avatar
pixhawk committed
216 217
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
218

219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239
        bool multiComponentSourceDetected = false;
        bool wrongComponent = false;

        // Store component ID
        if (componentID[message.msgid] == -1)
        {
            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;


240 241
        switch (message.msgid)
        {
pixhawk's avatar
pixhawk committed
242
        case MAVLINK_MSG_ID_HEARTBEAT:
243
        {
244
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
245
            emit heartbeat(this);
246 247
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
pixhawk's avatar
pixhawk committed
248
            // Set new type if it has changed
249
            if (this->type != state.type)
250
            {
251
                this->type = state.type;
252 253 254 255
                if (airframe == 0)
                {
                    switch (type)
                    {
lm's avatar
lm committed
256
                    case MAV_TYPE_FIXED_WING:
257 258
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
lm's avatar
lm committed
259
                    case MAV_TYPE_QUADROTOR:
260 261
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
262 263 264
                    case MAV_TYPE_HEXAROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
                        break;
265 266 267 268 269
                    default:
                        // Do nothing
                        break;
                    }
                }
270
                this->autopilot = state.autopilot;
pixhawk's avatar
pixhawk committed
271 272
                emit systemTypeSet(this, type);
            }
273

274 275 276 277 278 279 280 281 282 283 284 285 286 287 288
            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();
                }
            }
289

290 291 292 293 294 295
            QString audiostring = "System " + getUASName();
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
296 297


298 299 300 301 302 303 304
            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);
305

306
                shortStateText = uasState;
307

308 309
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
310

311
            if (this->mode != static_cast<int>(state.base_mode))
312 313
            {
                modechanged = true;
314
                this->mode = static_cast<int>(state.base_mode);
315
                shortModeText = getShortModeTextFor(this->mode);
316

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

319 320
                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed
321

322
            if (navMode != state.custom_mode)
323
            {
324 325
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
326 327
                navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
            }
328

329 330 331 332 333 334 335 336 337 338 339
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
340

341 342 343 344 345 346 347
            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();
348
                GAudioOutput::instance()->say(audiostring.toLower());
349
            }
lm's avatar
lm committed
350

351 352 353 354 355
//            if (state.system_status == MAV_STATE_POWEROFF)
//            {
//                emit systemRemoved(this);
//                emit systemRemoved();
//            }
356
}
357

358 359 360 361 362 363 364 365
            break;
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
            // Receive named value message
            receiveMessageNamedValue(message);
            break;
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
366 367 368 369
                if (multiComponentSourceDetected && message.compid != MAV_COMP_ID_IMU_2)
                {
                    break;
                }
370 371
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
372

373
                emit loadChanged(this,state.load/10.0f);
LM's avatar
LM committed
374

375
                currentVoltage = state.voltage_battery/1000.0f;
LM's avatar
LM committed
376
                lpVoltage = filterVoltage(currentVoltage);
LM's avatar
LM committed
377

LM's avatar
LM committed
378 379
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
380
                if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
381
                {
382
                    chargeLevel = state.battery_remaining;
LM's avatar
LM committed
383 384 385
                }
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
386
                emit voltageChanged(message.sysid, state.voltage_battery/1000);
387

LM's avatar
LM committed
388
                // LOW BATTERY ALARM
389 390
                if (lpVoltage < warnVoltage)
                {
LM's avatar
LM committed
391
                    startLowBattAlarm();
392 393 394
                }
                else
                {
LM's avatar
LM committed
395 396
                    stopLowBattAlarm();
                }
397

LM's avatar
LM committed
398
                // COMMUNICATIONS DROP RATE
399 400
                // FIXME
                emit dropRateChanged(this->getUASID(), state.drop_rate_comm/10000.0f);
401
            }
LM's avatar
LM committed
402
            break;
pixhawk's avatar
pixhawk committed
403
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
404
            {
405 406
                if (wrongComponent) break;

LM's avatar
LM committed
407 408
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
409
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
LM's avatar
LM committed
410
                lastAttitude = time;
LM's avatar
LM committed
411 412 413 414
                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);

415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430
//                // 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;
//                }
lm's avatar
lm committed
431

LM's avatar
LM committed
432
                attitudeKnown = true;
433
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
434
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
435
            }
LM's avatar
LM committed
436
            break;
lm's avatar
lm committed
437 438 439 440
        case MAVLINK_MSG_ID_HIL_CONTROLS:
            {
                mavlink_hil_controls_t hil;
                mavlink_msg_hil_controls_decode(&message, &hil);
441
                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
442 443
            }
            break;
444 445
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
446 447 448 449 450 451
                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);

452 453
                if (!attitudeKnown)
                {
LM's avatar
LM committed
454 455 456
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
457

LM's avatar
LM committed
458
                emit altitudeChanged(uasId, hud.alt);
LM's avatar
LM committed
459
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
LM's avatar
LM committed
460 461
            }
            break;
lm's avatar
lm committed
462
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
lm's avatar
lm committed
463
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
464
            //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
465
            {
lm's avatar
lm committed
466 467
                mavlink_local_position_ned_t pos;
                mavlink_msg_local_position_ned_decode(&message, &pos);
468
                quint64 time = getUnixTime(pos.time_boot_ms);
LM's avatar
LM committed
469 470 471 472 473 474 475 476 477 478 479 480
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);

                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
481
                isLocalPositionKnown = true;
lm's avatar
lm committed
482
            }
LM's avatar
LM committed
483
            break;
484
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
485 486
            //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
487 488 489 490 491 492 493 494 495 496 497 498 499
            {
                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);
                // Set internal state
500 501
                if (!positionLock)
                {
LM's avatar
LM committed
502 503 504 505
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
506
                isGlobalPositionKnown = true;
LM's avatar
LM committed
507 508
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
509
            }
LM's avatar
LM committed
510
            break;
511 512
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
LM's avatar
LM committed
513 514 515 516 517
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);

                // SANITY CHECK
                // only accept values in a realistic range
518 519
                // quint64 time = getUnixTime(pos.time_usec);
                quint64 time = getUnixTime(pos.time_usec);
LM's avatar
LM committed
520

521 522
                if (pos.fix_type > 2)
                {
LM's avatar
LM committed
523 524 525 526 527
                    emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
                    latitude = pos.lat/(double)1E7;
                    longitude = pos.lon/(double)1E7;
                    altitude = pos.alt/1000.0;
                    positionLock = true;
528
                    isGlobalPositionKnown = true;
LM's avatar
LM committed
529 530 531

                    // Check for NaN
                    int alt = pos.alt;
532 533
                    if (!isnan(alt) && !isinf(alt))
                    {
LM's avatar
LM committed
534
                        alt = 0;
535
                        //emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE");
LM's avatar
LM committed
536
                    }
lm's avatar
lm committed
537
                    // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
LM's avatar
LM committed
538
                    // Smaller than threshold and not NaN
LM's avatar
LM committed
539 540 541

                    float vel = pos.vel/100.0f;

542 543
                    if (vel < 1000000 && !isnan(vel) && !isinf(vel))
                    {
lm's avatar
lm committed
544
                        // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time);
LM's avatar
LM committed
545 546
                        //qDebug() << "GOT GPS RAW";
                        // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
547 548 549
                    }
                    else
                    {
LM's avatar
LM committed
550
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
LM's avatar
LM committed
551
                    }
lm's avatar
lm committed
552 553
                }
            }
LM's avatar
LM committed
554
            break;
555 556
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
LM's avatar
LM committed
557 558
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
559 560
                for(int i = 0; i < (int)pos.satellites_visible; i++)
                {
LM's avatar
LM committed
561 562
                    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]));
                }
563
            }
LM's avatar
LM committed
564
            break;
565
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
566
            {
567 568
                mavlink_gps_global_origin_t pos;
                mavlink_msg_gps_global_origin_decode(&message, &pos);
LM's avatar
LM committed
569
                emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
LM's avatar
LM committed
570 571
            }
            break;
572 573
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            {
LM's avatar
LM committed
574 575 576 577 578 579 580 581 582 583 584 585 586
                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);
            }
            break;
587 588
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
LM's avatar
LM committed
589 590 591 592 593 594 595 596 597 598 599
                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
600
            }
LM's avatar
LM committed
601
            break;
602 603
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
LM's avatar
LM committed
604 605
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
606
                QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
LM's avatar
LM committed
607 608
                QString parameterName = QString(bytes);
                int component = message.compid;
609 610
                mavlink_param_union_t val;
                val.param_float = value.param_value;
611
                val.type = value.param_type;
612

LM's avatar
LM committed
613
                // Insert component if necessary
614 615
                if (!parameters.contains(component))
                {
616
                    parameters.insert(component, new QMap<QString, QVariant>());
LM's avatar
LM committed
617
                }
618

LM's avatar
LM committed
619 620
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
621

622 623 624
                // Insert with correct type
                switch (value.param_type)
                {
625
                case MAVLINK_TYPE_FLOAT:
626 627 628 629
                    {
                    // Variant
                    QVariant param(val.param_float);
                    parameters.value(component)->insert(parameterName, param);
630
                    // Emit change
631 632 633 634
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
635
                    break;
636
                case MAVLINK_TYPE_UINT32_T:
637 638 639 640
                    {
                    // Variant
                    QVariant param(val.param_uint32);
                    parameters.value(component)->insert(parameterName, param);
641
                    // Emit change
642 643 644 645
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
646
                    break;
647
                case MAVLINK_TYPE_INT32_T:
648 649 650 651
                    {
                    // Variant
                    QVariant param(val.param_int32);
                    parameters.value(component)->insert(parameterName, param);
652
                    // Emit change
653 654 655 656
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
657 658 659 660
                    break;
                default:
                    qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
                }
LM's avatar
LM committed
661 662
            }
            break;
663 664 665
        case MAVLINK_MSG_ID_COMMAND_ACK:
            mavlink_command_ack_t ack;
            mavlink_msg_command_ack_decode(&message, &ack);
666 667
            if (ack.result == 1)
            {
668
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
669 670 671
            }
            else
            {
672
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
673 674
            }
            break;
LM's avatar
LM committed
675
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
676
            {
LM's avatar
LM committed
677 678
                mavlink_roll_pitch_yaw_thrust_setpoint_t out;
                mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
679
                quint64 time = getUnixTimeFromMs(out.time_boot_ms);
LM's avatar
LM committed
680
                emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
LM's avatar
LM committed
681 682
            }
            break;
lm's avatar
lm committed
683
        case MAVLINK_MSG_ID_MISSION_COUNT:
684
            {
lm's avatar
lm committed
685 686
                mavlink_mission_count_t wpc;
                mavlink_msg_mission_count_decode(&message, &wpc);
687
                if (wpc.target_system == mavlink->getSystemId())
688
                {
LM's avatar
LM committed
689 690
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
LM's avatar
LM committed
691 692 693 694
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
695
            }
LM's avatar
LM committed
696
            break;
pixhawk's avatar
pixhawk committed
697

lm's avatar
lm committed
698
        case MAVLINK_MSG_ID_MISSION_ITEM:
699
            {
lm's avatar
lm committed
700 701
                mavlink_mission_item_t wp;
                mavlink_msg_mission_item_decode(&message, &wp);
LM's avatar
LM committed
702
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
703
                if(wp.target_system == mavlink->getSystemId())
704
                {
LM's avatar
LM committed
705 706
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
LM's avatar
LM committed
707 708 709 710
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
711
            }
LM's avatar
LM committed
712
            break;
pixhawk's avatar
pixhawk committed
713

lm's avatar
lm committed
714
        case MAVLINK_MSG_ID_MISSION_ACK:
715
            {
lm's avatar
lm committed
716 717
                mavlink_mission_ack_t wpa;
                mavlink_msg_mission_ack_decode(&message, &wpa);
718 719
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
720 721
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
722
            }
LM's avatar
LM committed
723
            break;
724

lm's avatar
lm committed
725
        case MAVLINK_MSG_ID_MISSION_REQUEST:
726
            {
lm's avatar
lm committed
727 728
                mavlink_mission_request_t wpr;
                mavlink_msg_mission_request_decode(&message, &wpr);
729
                if(wpr.target_system == mavlink->getSystemId())
730
                {
LM's avatar
LM committed
731 732
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
LM's avatar
LM committed
733 734 735 736
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
737
            }
LM's avatar
LM committed
738
            break;
pixhawk's avatar
pixhawk committed
739

lm's avatar
lm committed
740
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
741
            {
lm's avatar
lm committed
742 743
                mavlink_mission_item_reached_t wpr;
                mavlink_msg_mission_item_reached_decode(&message, &wpr);
LM's avatar
LM committed
744 745 746 747 748 749
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
                QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq);
                GAudioOutput::instance()->say(text);
                emit textMessageReceived(message.sysid, message.compid, 0, text);
            }
            break;
pixhawk's avatar
pixhawk committed
750

lm's avatar
lm committed
751
        case MAVLINK_MSG_ID_MISSION_CURRENT:
752
            {
lm's avatar
lm committed
753 754
                mavlink_mission_current_t wpc;
                mavlink_msg_mission_current_decode(&message, &wpc);
LM's avatar
LM committed
755 756 757
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
758

759 760
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
761 762 763 764 765
                mavlink_local_position_setpoint_t p;
                mavlink_msg_local_position_setpoint_decode(&message, &p);
                emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs());
            }
            break;
766 767
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
768 769
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
lm's avatar
lm committed
770
                mavlink_msg_statustext_get_text(&message, b.data());
LM's avatar
LM committed
771 772 773 774 775 776 777 778
                //b.append('\0');
                QString text = QString(b);
                int severity = mavlink_msg_statustext_get_severity(&message);
                //qDebug() << "RECEIVED STATUS:" << text;false
                //emit statusTextReceived(severity, text);
                emit textMessageReceived(uasId, message.compid, severity, text);
            }
            break;
779
#ifdef MAVLINK_ENABLED_PIXHAWK
780 781
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
782 783 784 785 786 787 788 789 790 791 792
                qDebug() << "RECIEVED ACK TO GET IMAGE";
                mavlink_data_transmission_handshake_t p;
                mavlink_msg_data_transmission_handshake_decode(&message, &p);
                imageSize = p.size;
                imagePackets = p.packets;
                imagePayload = p.payload;
                imageQuality = p.jpg_quality;
                imageType = p.type;
                imageStart = QGC::groundTimeMilliseconds();
            }
            break;
793

794 795
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
796 797 798 799 800 801 802 803 804 805 806
                mavlink_encapsulated_data_t img;
                mavlink_msg_encapsulated_data_decode(&message, &img);
                int seq = img.seqnr;
                int pos = seq * imagePayload;

                // Check if we have a valid transaction
                if (imagePackets == 0)
                {
                    // NO VALID TRANSACTION - ABORT
                    // Restart statemachine
                    imagePacketsArrived = 0;
807 808
                }

809 810
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
811 812 813 814 815
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
816

LM's avatar
LM committed
817
                ++imagePacketsArrived;
818

LM's avatar
LM committed
819 820 821 822 823 824 825 826
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    imagePacketsArrived = 0;
                    emit imageReady(this);
                    qDebug() << "imageReady emitted. all packets arrived";
                }
827
            }
LM's avatar
LM committed
828
            break;
829
#endif
lm's avatar
lm committed
830 831 832 833 834 835 836 837
//        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;
838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856
        // 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++)
lm's avatar
lm committed
857
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
858 859 860
//                    break;
//                case 1:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
861
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
862 863 864
//                    break;
//                case 2:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
865
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
866 867 868
//                    break;
//                case 3:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
869
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
870 871 872
//                    break;
//                case 4:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
873
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
874 875 876
//                    break;
//                case 5:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
877
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
878 879 880
//                    break;
//                case 6:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
881
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
882 883 884 885 886
//                    break;
//                }
//            }
//        }
//        break;
lm's avatar
lm committed
887
#ifdef MAVLINK_ENABLED_UALBERTA
888 889
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
LM's avatar
LM committed
890 891 892
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = getUnixTime();
lm's avatar
lm committed
893 894 895 896 897 898
                // 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
899 900
            }
            break;
901 902
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
LM's avatar
LM committed
903 904
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
905 906 907 908 909 910
                QVector<uint16_t> aileron;
                QVector<uint16_t> elevator;
                QVector<uint16_t> rudder;
                QVector<uint16_t> gyro;
                QVector<uint16_t> pitch;
                QVector<uint16_t> throttle;
LM's avatar
LM committed
911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929

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

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

931
#endif
LM's avatar
LM committed
932
            // Messages to ignore
933
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
lm's avatar
lm committed
934 935 936 937 938 939 940
        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:
941
            break;
lm's avatar
lm committed
942
        case MAVLINK_MSG_ID_DEBUG_VECT:
LM's avatar
LM committed
943 944 945
            {
                mavlink_debug_vect_t debug;
                mavlink_msg_debug_vect_decode(&message, &debug);
946
                debug.name[MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN-1] = '\0';
LM's avatar
LM committed
947 948 949 950 951 952 953
                QString name(debug.name);
                quint64 time = getUnixTime(debug.time_usec);
                emit valueChanged(uasId, name+".x", "raw", debug.x, time);
                emit valueChanged(uasId, name+".y", "raw", debug.y, time);
                emit valueChanged(uasId, name+".z", "raw", debug.z, time);
            }
            break;
LM's avatar
LM committed
954
        case MAVLINK_MSG_ID_DEBUG:
955
            break;
956 957 958 959
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
960 961 962 963 964 965 966
                    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
967
            }
LM's avatar
LM committed
968
            break;
pixhawk's avatar
pixhawk committed
969 970 971 972
        }
    }
}

973 974 975 976 977 978 979 980 981 982 983 984
#ifdef QGC_PROTOBUF_ENABLED
void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message)
{
    if (!link) return;
    if (!links->contains(link))
    {
        addLink(link);
    }

    if (message->GetTypeName() == pointCloud.GetTypeName())
    {
        pointCloud.CopyFrom(*message);
985
        emit pointCloudChanged(this);
986
    }
987 988 989
    else if (message->GetTypeName() == rgbdImage.GetTypeName())
    {
        rgbdImage.CopyFrom(*message);
990
        emit rgbdImageChanged(this);
991
    }
992 993 994 995
}

#endif

996 997
void UAS::setHomePosition(double lat, double lon, double alt)
{
998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030
    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);
        // Wait 15 ms
        QGC::SLEEP::usleep(15000);
        // Send again
        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);
    }
1031 1032
}

1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046
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()));


1047 1048
    if (ret == QMessageBox::Yes)
    {
1049 1050 1051 1052 1053 1054 1055 1056
        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);
        // Wait 15 ms
        QGC::SLEEP::usleep(15000);
        // Send again
        sendMessage(msg);
1057 1058 1059
    }
}

pixhawk's avatar
pixhawk committed
1060 1061
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1062
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1063
    mavlink_message_t msg;
LM's avatar
LM committed
1064
    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
1065
    sendMessage(msg);
1066
#else
lm's avatar
lm committed
1067 1068 1069 1070
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1071
#endif
pixhawk's avatar
pixhawk committed
1072 1073
}

pixhawk's avatar
pixhawk committed
1074 1075
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1076
#ifdef MAVLINK_ENABLED_PIXHAWK
1077
    mavlink_message_t msg;
1078
    mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
1079
    sendMessage(msg);
lm's avatar
lm committed
1080
#else
1081 1082 1083 1084
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1085 1086 1087 1088
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1089
{
1090 1091
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1092
    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);
1093
    sendMessage(msg);
lm's avatar
lm committed
1094 1095
}

1096
void UAS::startDataRecording()
lm's avatar
lm committed
1097
{
1098
    mavlink_message_t msg;
1099
    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);
1100
    sendMessage(msg);
lm's avatar
lm committed
1101 1102 1103 1104
}

void UAS::stopDataRecording()
{
1105
    mavlink_message_t msg;
1106
    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);
1107
    sendMessage(msg);
lm's avatar
lm committed
1108 1109
}

pixhawk's avatar
pixhawk committed
1110 1111
void UAS::startMagnetometerCalibration()
{
1112 1113
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1114
    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);
1115
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1116 1117 1118 1119
}

void UAS::startGyroscopeCalibration()
{
1120 1121
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1122
    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);
1123
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1124 1125 1126 1127
}

void UAS::startPressureCalibration()
{
1128 1129
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1130
    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);
1131
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1132 1133
}

LM's avatar
LM committed
1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178
quint64 UAS::getUnixReferenceTime(quint64 time)
{
    // Same as getUnixTime, but does not react to attitudeStamped mode
    if (time == 0)
    {
        //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
        return QGC::groundTimeMilliseconds();
    }
    // Check if time is smaller than 40 years,
    // assuming no system without Unix timestamp
    // runs longer than 40 years continuously without
    // reboot. In worst case this will add/subtract the
    // communication delay between GCS and MAV,
    // it will never alter the timestamp in a safety
    // critical way.
    //
    // Calculation:
    // 40 years
    // 365 days
    // 24 hours
    // 60 minutes
    // 60 seconds
    // 1000 milliseconds
    // 1000 microseconds
#ifndef _MSC_VER
    else if (time < 1261440000000000LLU)
#else
        else if (time < 1261440000000000)
#endif
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
        if (onboardTimeOffset == 0)
        {
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
        }
        return time/1000 + onboardTimeOffset;
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
        return time/1000;
    }
}

1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191
/**
 * @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
1192 1193 1194 1195 1196 1197 1198 1199
/**
 * @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!
 */
1200 1201
quint64 UAS::getUnixTime(quint64 time)
{
1202
    quint64 ret = 0;
LM's avatar
LM committed
1203 1204
    if (attitudeStamped)
    {
1205
        ret = lastAttitude;
LM's avatar
LM committed
1206
    }
1207 1208
    if (time == 0)
    {
1209
        ret = QGC::groundTimeMilliseconds();
1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226
    }
    // 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
1227
#ifndef _MSC_VER
1228
    else if (time < 1261440000000000LLU)
1229
#else
LM's avatar
LM committed
1230
        else if (time < 1261440000000000)
1231
#endif
LM's avatar
LM committed
1232 1233
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1234 1235
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1236
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1237
        }
1238
        ret = time/1000 + onboardTimeOffset;
1239 1240 1241
    }
    else
    {
1242 1243
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1244
        ret = time/1000;
1245
    }
1246
    return ret;
1247 1248
}

1249 1250
QList<QString> UAS::getParameterNames(int component)
{
1251 1252
    if (parameters.contains(component))
    {
1253
        return parameters.value(component)->keys();
1254 1255 1256
    }
    else
    {
1257 1258 1259 1260 1261 1262 1263 1264 1265
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1266
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1267
{
LM's avatar
LM committed
1268 1269 1270 1271 1272
    //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
1273 1274 1275 1276 1277
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1278 1279 1280 1281
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1282
            sendMessage(link, message);
1283 1284 1285
        }
        else
        {
1286 1287 1288
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1289 1290 1291
    }
}

1292 1293 1294 1295
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);