UAS.cc 83.8 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 985 986 987 988 989
#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);
    }
}

#endif

990 991
void UAS::setHomePosition(double lat, double lon, double alt)
{
992 993 994 995 996 997 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
    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);
    }
1025 1026
}

1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040
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()));


1041 1042
    if (ret == QMessageBox::Yes)
    {
1043 1044 1045 1046 1047 1048 1049 1050
        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);
1051 1052 1053
    }
}

pixhawk's avatar
pixhawk committed
1054 1055
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1056
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1057
    mavlink_message_t msg;
LM's avatar
LM committed
1058
    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
1059
    sendMessage(msg);
1060
#else
lm's avatar
lm committed
1061 1062 1063 1064
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1065
#endif
pixhawk's avatar
pixhawk committed
1066 1067
}

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

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1083
{
1084 1085
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1086
    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);
1087
    sendMessage(msg);
lm's avatar
lm committed
1088 1089
}

1090
void UAS::startDataRecording()
lm's avatar
lm committed
1091
{
1092
    mavlink_message_t msg;
1093
    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);
1094
    sendMessage(msg);
lm's avatar
lm committed
1095 1096 1097 1098
}

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

pixhawk's avatar
pixhawk committed
1104 1105
void UAS::startMagnetometerCalibration()
{
1106 1107
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1108
    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);
1109
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1110 1111 1112 1113
}

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

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

LM's avatar
LM committed
1128 1129 1130 1131 1132 1133 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
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;
    }
}

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

1243 1244
QList<QString> UAS::getParameterNames(int component)
{
1245 1246
    if (parameters.contains(component))
    {
1247
        return parameters.value(component)->keys();
1248 1249 1250
    }
    else
    {
1251 1252 1253 1254 1255 1256 1257 1258 1259
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1260
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1261
{
LM's avatar
LM committed
1262 1263 1264 1265 1266
    //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
1267 1268 1269 1270 1271
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1272 1273 1274 1275
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1276
            sendMessage(link, message);
1277 1278 1279
        }
        else
        {
1280 1281 1282
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1283 1284 1285
    }
}

1286 1287 1288 1289
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1290

1291 1292 1293 1294
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1295
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1296 1297 1298 1299 1300 1301
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1302
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1303 1304
                        sendMessage(serial, message);
                    }
1305 1306 1307 1308 1309 1310
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1311 1312
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1313
    if(!link) return;
pixhawk's avatar
pixhawk committed
1314 1315 1316
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1317
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1318 1319
    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
1320
    // If link is connected
1321 1322
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1323 1324 1325 1326 1327 1328 1329 1330
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1331
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1332
{
1333
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1334 1335
}

1336 1337
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1338 1339
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
1340 1341
    switch (mode)
    {
lm's avatar
lm committed
1342
    case 0:
1343
        return QString("PREFLIGHT");
1344 1345 1346 1347
        break;
    default:
        return QString("UNKNOWN");
    }
lm's avatar
lm committed
1348 1349 1350 1351 1352 1353 1354 1355 1356
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1357 1358
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1359 1360
}

pixhawk's avatar
pixhawk committed
1361 1362
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1363 1364
    switch (statusCode)
    {
lm's avatar
lm committed
1365
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1366
        uasState = tr("UNINIT");
1367
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1368
        break;
lm's avatar
lm committed
1369
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1370
        uasState = tr("BOOT");
1371
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1372
        break;
lm's avatar
lm committed
1373
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1374
        uasState = tr("CALIBRATING");
1375
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1376
        break;
lm's avatar
lm committed
1377
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1378
        uasState = tr("ACTIVE");
1379
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1380
        break;
lm's avatar
lm committed
1381 1382
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1383
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1384 1385
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1386
        uasState = tr("CRITICAL");
1387
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1388
        break;
lm's avatar
lm committed
1389
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1390
        uasState = tr("EMERGENCY");
1391
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1392
        break;
James Goppert's avatar
James Goppert committed
1393
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1394 1395 1396
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1397

lm's avatar
lm committed
1398
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1399
        uasState = tr("SHUTDOWN");
1400
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1401
        break;
1402

lm's avatar
lm committed
1403
    default:
pixhawk's avatar
pixhawk committed
1404
        uasState = tr("UNKNOWN");
1405
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1406 1407 1408 1409
        break;
    }
}

1410 1411
QImage UAS::getImage()
{
LM's avatar
LM committed
1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458
#ifdef MAVLINK_ENABLED_PIXHAWK

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

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

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

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

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

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

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

    }
    // BMP with header
    else if (imageType == MAVLINK_DATA_STREAM_IMG_BMP ||
             imageType == MAVLINK_DATA_STREAM_IMG_JPEG ||
             imageType == MAVLINK_DATA_STREAM_IMG_PGM ||
             imageType == MAVLINK_DATA_STREAM_IMG_PNG)
    {
       if (!image.loadFromData(imageRecBuffer))
        {
           qDebug() << "Loading data from image buffer failed!";
        }
    }
1459 1460
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1461
    //imageRecBuffer.clear();
1462
    return image;
1463 1464
#else
	return QImage();
LM's avatar
LM committed
1465
#endif
1466

1467 1468 1469 1470
}

void UAS::requestImage()
{
1471
#ifdef MAVLINK_ENABLED_PIXHAWK
1472 1473
    qDebug() << "trying to get an image from the uas...";

1474 1475 1476
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1477 1478 1479 1480
        mavlink_message_t msg;
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 50);
        sendMessage(msg);
    }
1481
#endif
1482
}
pixhawk's avatar
pixhawk committed
1483 1484 1485 1486 1487 1488 1489 1490 1491


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1492
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1493
{
1494 1495
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1496
        return 0;
1497 1498 1499
    }
    else
    {
pixhawk's avatar
pixhawk committed
1500 1501 1502 1503
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1504
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1505 1506 1507 1508
{
    return commStatus;
}

1509 1510 1511
void UAS::requestParameters()
{
    mavlink_message_t msg;
1512
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1513
    sendMessage(msg);
1514 1515
}

1516
void UAS::writeParametersToStorage()
1517
{
1518
    mavlink_message_t msg;
1519
    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
1520
    qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
1521
    sendMessage(msg);
1522 1523 1524 1525
}

void UAS::readParametersFromStorage()
{
1526
    mavlink_message_t msg;
1527
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
1528
    sendMessage(msg);
lm's avatar
lm committed
1529 1530
}

1531
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1532 1533
{
    // Buffers to write data to
1534
    mavlink_message_t msg;
1535
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1536 1537
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1538
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1539 1540
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1541 1542
    // 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
1543 1544
    stream.req_message_rate = 0;
    // Start / stop the message
1545
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1546 1547 1548 1549 1550
    // 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
1551
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1552 1553
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1554 1555
}

1556
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1557 1558 1559
{
    // Buffers to write data to
    mavlink_message_t msg;
1560
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1561
    // Select the message to request from now on
1562
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1563
    // Select the update rate in Hz the message should be send
1564
    stream.req_message_rate = rate;
lm's avatar
lm committed
1565
    // Start / stop the message
1566
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1567 1568 1569 1570 1571
    // 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
1572
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1573 1574
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1575 1576
}

1577
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1578
{
1579 1580 1581 1582
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1583
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1584
    // Select the update rate in Hz the message should be send
1585
    stream.req_message_rate = rate;
1586
    // Start / stop the message
1587
    stream.start_stop = (rate) ? 1 : 0;
1588 1589 1590 1591 1592 1593
    // 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);
1594 1595
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1596
}
1597

1598
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1599
{
1600 1601 1602 1603 1604
#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
1605 1606 1607
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1608
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1609
    // Select the update rate in Hz the message should be send
1610
    stream.req_message_rate = rate;
1611
    // Start / stop the message
1612
    stream.start_stop = (rate) ? 1 : 0;
1613 1614 1615 1616 1617 1618
    // 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);
1619 1620
    // Send message twice to increase chance of reception
    sendMessage(msg);
1621
#endif
lm's avatar
lm committed
1622 1623
}

1624
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1625
{
1626 1627 1628 1629
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1630
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1631
    // Select the update rate in Hz the message should be send
1632
    stream.req_message_rate = rate;
1633
    // Start / stop the message
1634
    stream.start_stop = (rate) ? 1 : 0;
1635 1636 1637 1638 1639 1640
    // 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);
1641 1642
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1643 1644
}

lm's avatar
lm committed
1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665
//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);
//}
1666

1667
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1668 1669 1670 1671 1672
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1673
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1674
    // Select the update rate in Hz the message should be send
1675
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1676
    // Start / stop the message
1677
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1678 1679 1680 1681 1682 1683 1684 1685 1686 1687
    // 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);
}

1688
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1689 1690 1691 1692 1693
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1694
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1695
    // Select the update rate in Hz the message should be send
1696
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1697
    // Start / stop the message
1698
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709
    // 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);
}

1710
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1711 1712 1713 1714 1715
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1716
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1717
    // Select the update rate in Hz the message should be send
1718
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1719
    // Start / stop the message
1720
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731
    // 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);
}

1732
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1733 1734 1735 1736 1737
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1738
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1739
    // Select the update rate in Hz the message should be send
1740
    stream.req_message_rate = rate;
1741
    // Start / stop the message
1742
    stream.start_stop = (rate) ? 1 : 0;
1743 1744 1745 1746 1747 1748
    // 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);
1749 1750
    // Send message twice to increase chance of reception
    sendMessage(msg);
1751
    sendMessage(msg);
1752 1753
}

lm's avatar
lm committed
1754 1755 1756 1757 1758 1759 1760
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1761
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
lm's avatar
lm committed
1762
{
1763 1764
    if (!id.isNull())
    {
1765 1766
        mavlink_message_t msg;
        mavlink_param_set_t p;
1767 1768 1769 1770 1771 1772 1773
        mavlink_param_union_t union_value;

        // Assign correct value based on QVariant
        switch (value.type())
        {
        case QVariant::Int:
            union_value.param_int32 = value.toInt();
1774
            p.param_type = MAVLINK_TYPE_INT32_T;
1775 1776 1777
            break;
        case QVariant::UInt:
            union_value.param_uint32 = value.toUInt();
1778
            p.param_type = MAVLINK_TYPE_UINT32_T;
1779 1780 1781
            break;
        case QMetaType::Float:
            union_value.param_float = value.toFloat();
1782
            p.param_type = MAVLINK_TYPE_FLOAT;
1783 1784 1785 1786 1787 1788 1789
            break;
        default:
            qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
            return;
        }

        p.param_value = union_value.param_float;
1790 1791 1792
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

1793 1794
        qDebug() << "SENT PARAM:" << value;

1795
        // Copy string into buffer, ensuring not to exceed the buffer size
1796 1797
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1798
            // String characters
1799 1800
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1801 1802
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1803 1804 1805 1806 1807
            //        // 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';
            //        }
1808
            // Zero fill
1809 1810
            else
            {
1811 1812
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1813
        }
1814 1815
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1816
    }
1817 1818
}

1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832
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;
}

1833
void UAS::requestParameter(int component, const QString& parameter)
1834
{
1835
    // Request parameter, use parameter name to request it
1836 1837
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
1838 1839 1840 1841 1842 1843 1844 1845
    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
1846 1847 1848 1849
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
1850
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
1851 1852
}

1853 1854 1855 1856
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
1857 1858 1859 1860
    if (airframe == 0)
    {
        switch (systemType)
        {
lm's avatar
lm committed
1861
        case MAV_TYPE_FIXED_WING:
1862 1863
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
lm's avatar
lm committed
1864
        case MAV_TYPE_QUADROTOR:
1865 1866 1867 1868 1869 1870 1871
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1872 1873
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
1874 1875 1876 1877 1878 1879 1880
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
1881 1882
}

lm's avatar
lm committed
1883 1884 1885
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
1886
    mavlink_command_long_t cmd;
1887 1888 1889 1890 1891 1892
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
1893 1894 1895
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
1896 1897
    cmd.target_system = uasId;
    cmd.target_component = 0;
1898
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1899 1900 1901 1902 1903 1904
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
1905
    mavlink_command_long_t cmd;
1906 1907 1908 1909 1910 1911
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1912 1913 1914
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
1915 1916
    cmd.target_system = uasId;
    cmd.target_component = component;
1917
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1918 1919 1920 1921 1922 1923 1924
    sendMessage(msg);
}

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;
1925 1926 1927 1928 1929 1930
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1931 1932 1933
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
1934 1935
    cmd.target_system = uasId;
    cmd.target_component = component;
1936
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
1937 1938 1939
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1940
/**
lm's avatar
lm committed
1941
 * Launches the system
pixhawk's avatar
pixhawk committed
1942 1943 1944 1945
 *
 **/
void UAS::launch()
{
1946
    mavlink_message_t msg;
1947
    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);
1948
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1949 1950 1951 1952 1953 1954
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
1955
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
1956
{
1957
    mavlink_message_t msg;
1958
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
1959
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1960 1961 1962 1963 1964 1965
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
1966
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
1967
{
1968
    mavlink_message_t msg;
1969
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
1970
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1971 1972 1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983 1984
}

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
1985 1986
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
1987
    {
1988 1989 1990 1991
        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
1992

1993
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
1994 1995 1996
    }
    else
    {
1997 1998
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
1999 2000
}

2001 2002 2003 2004 2005
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2006 2007
void UAS::receiveButton(int buttonIndex)
{
2008 2009
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2010
    case 0:
pixhawk's avatar
pixhawk committed
2011

pixhawk's avatar
pixhawk committed
2012 2013
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2014

pixhawk's avatar
pixhawk committed
2015 2016 2017 2018 2019
        break;
    default:

        break;
    }
2020
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2021 2022 2023

}

2024

pixhawk's avatar
pixhawk committed
2025 2026
void UAS::halt()
{
2027 2028 2029
    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
2030 2031 2032 2033
}

void UAS::go()
{
2034 2035 2036
    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
2037 2038 2039 2040 2041
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
2042 2043 2044 2045 2046 2047 2048 2049 2050
    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
2051 2052 2053 2054 2055 2056 2057 2058
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2059 2060
    // FIXME MAVLINKV10PORTINGNEEDED
    halt();
pixhawk's avatar
pixhawk committed
2061 2062 2063
}

/**
lm's avatar
lm committed
2064
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2065 2066 2067 2068 2069 2070
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
2071
    halt();
lm's avatar
lm committed
2072 2073 2074 2075 2076 2077 2078 2079 2080 2081 2082 2083 2084 2085 2086 2087 2088 2089 2090 2091 2092 2093 2094 2095 2096 2097
    // FIXME MAVLINKV10PORTINGNEEDED
//    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;
    return false;
pixhawk's avatar
pixhawk committed
2098 2099
}

lm's avatar
lm committed
2100 2101 2102 2103 2104
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2105
        startHil();
lm's avatar
lm committed
2106 2107 2108
    }
    else
    {
2109
        stopHil();
lm's avatar
lm committed
2110 2111 2112 2113 2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134 2135 2136 2137 2138 2139 2140
    }
}

/**
* @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,
                    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)
{
    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);
}


2141 2142
void UAS::startHil()
{
lm's avatar
lm committed
2143 2144
    // Connect Flight Gear Link
    simulation->connectSimulation();
2145
    mavlink_message_t msg;
LM's avatar
LM committed
2146
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
2147
    sendMessage(msg);
2148 2149
}

2150 2151
void UAS::stopHil()
{
lm's avatar
lm committed
2152
    simulation->disconnectSimulation();
2153
    mavlink_message_t msg;
LM's avatar
LM committed
2154
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
2155
    sendMessage(msg);
2156 2157 2158
}


pixhawk's avatar
pixhawk committed
2159 2160
void UAS::shutdown()
{
2161 2162 2163 2164 2165
    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
2166

2167 2168 2169
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2170

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

2174 2175 2176 2177
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2178
        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);
2179 2180 2181
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2182 2183
}

2184 2185
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2186
    mavlink_message_t msg;
lm's avatar
lm committed
2187
    mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw);
2188
    sendMessage(msg);
2189 2190
}

pixhawk's avatar
pixhawk committed
2191 2192 2193
/**
 * @return The name of this system as string in human-readable form
 */
2194
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2195 2196
{
    QString result;
2197 2198
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2199
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2200 2201 2202
    }
    else
    {
pixhawk's avatar
pixhawk committed
2203 2204 2205 2206 2207
        result = name;
    }
    return result;
}

2208 2209 2210 2211 2212
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2213 2214 2215
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2216 2217 2218
    uint8_t modeid = id;

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

LM's avatar
LM committed
2220
    // BASE MODE DECODING
pixhawk's avatar
pixhawk committed
2221
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
LM's avatar
LM committed
2222
    {
pixhawk's avatar
pixhawk committed
2223
        mode += "AUTO";
LM's avatar
LM committed
2224
    }
pixhawk's avatar
pixhawk committed
2225
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
LM's avatar
LM committed
2226
    {
pixhawk's avatar
pixhawk committed
2227
        mode += "GUIDED";
LM's avatar
LM committed
2228
    }
pixhawk's avatar
pixhawk committed
2229
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
LM's avatar
LM committed
2230
    {
pixhawk's avatar
pixhawk committed
2231
        mode += "STABILIZED";
LM's avatar
LM committed
2232
    }
pixhawk's avatar
pixhawk committed
2233
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
LM's avatar
LM committed
2234
    {
pixhawk's avatar
pixhawk committed
2235
        mode += "TEST";
LM's avatar
LM committed
2236
    }
pixhawk's avatar
pixhawk committed
2237
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
LM's avatar
LM committed
2238
    {
pixhawk's avatar
pixhawk committed
2239
        mode += "MANUAL";
LM's avatar
LM committed
2240
    }
pixhawk's avatar
pixhawk committed
2241 2242

    if (modeid == 0)
LM's avatar
LM committed
2243
    {
2244
        mode = "PREFLIGHT";
LM's avatar
LM committed
2245 2246 2247
    }

    // ARMED STATE DECODING
pixhawk's avatar
pixhawk committed
2248
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
LM's avatar
LM committed
2249 2250 2251 2252 2253 2254 2255 2256 2257
    {
        mode.prepend("A|");
    }
    else
    {
        mode.prepend("D|");
    }

    // HARDWARE IN THE LOOP DECODING
pixhawk's avatar
pixhawk committed
2258
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
LM's avatar
LM committed
2259 2260
    {
        mode.prepend("HIL:");
2261 2262 2263 2264 2265
    }

    return mode;
}

2266 2267 2268 2269 2270
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2271 2272
void UAS::addLink(LinkInterface* link)
{
2273 2274
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2275
        links->append(link);
2276
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2277 2278 2279
    }
}

2280 2281 2282
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2283 2284
    if (link)
    {
2285 2286 2287 2288
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2289 2290 2291 2292 2293 2294 2295 2296 2297 2298 2299 2300 2301 2302 2303
/**
 * @brief Get the links associated with this robot
 *
 **/
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}



void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2304 2305
    switch (batteryType)
    {
lm's avatar
lm committed
2306
    case NICD:
pixhawk's avatar
pixhawk committed
2307
        break;
lm's avatar
lm committed
2308
    case NIMH:
pixhawk's avatar
pixhawk committed
2309
        break;
lm's avatar
lm committed
2310
    case LIION:
pixhawk's avatar
pixhawk committed
2311
        break;
lm's avatar
lm committed
2312
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2313 2314 2315
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2316
    case LIFE:
pixhawk's avatar
pixhawk committed
2317
        break;
lm's avatar
lm committed
2318
    case AGZN:
pixhawk's avatar
pixhawk committed
2319 2320 2321 2322
        break;
    }
}

2323 2324
void UAS::setBatterySpecs(const QString& specs)
{
2325 2326
    if (specs.length() == 0 || specs.contains("%"))
    {
2327
        batteryRemainingEstimateEnabled = false;
2328
        bool ok;
2329 2330 2331
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2332 2333
        if (ok)
        {
2334
            warnLevelPercent = temp;
2335 2336 2337
        }
        else
        {
2338 2339
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2340 2341 2342
    }
    else
    {
2343 2344 2345 2346 2347
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2348 2349
        if (parts.length() == 3)
        {
2350 2351 2352 2353 2354 2355 2356 2357 2358 2359 2360
            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;
2361 2362 2363
        }
        else
        {
2364 2365
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2366 2367 2368 2369 2370
    }
}

QString UAS::getBatterySpecs()
{
2371 2372
    if (batteryRemainingEstimateEnabled)
    {
2373
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2374 2375 2376
    }
    else
    {
2377 2378
        return QString("%1%").arg(warnLevelPercent);
    }
2379 2380
}

pixhawk's avatar
pixhawk committed
2381 2382 2383 2384 2385 2386 2387 2388 2389 2390 2391 2392 2393
int UAS::calculateTimeRemaining()
{
    quint64 dt = MG::TIME::getGroundTimeNow() - startTime;
    double seconds = dt / 1000.0f;
    double voltDifference = startVoltage - currentVoltage;
    if (voltDifference <= 0) voltDifference = 0.00000000001f;
    double dischargePerSecond = voltDifference / seconds;
    int remaining = static_cast<int>((currentVoltage - emptyVoltage) / dischargePerSecond);
    // Can never be below 0
    if (remaining < 0) remaining = 0;
    return remaining;
}

lm's avatar
lm committed
2394 2395 2396
/**
 * @return charge level in percent - 0 - 100
 */
2397
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2398
{
2399 2400 2401 2402
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2403
            chargeLevel = 0.0f;
2404 2405 2406
        }
        else if (lpVoltage > fullVoltage)
        {
2407
            chargeLevel = 100.0f;
2408 2409 2410
        }
        else
        {
2411 2412
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2413 2414
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2415 2416
}

lm's avatar
lm committed
2417 2418
void UAS::startLowBattAlarm()
{
2419 2420
    if (!lowBattAlarm)
    {
2421
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2422
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2423 2424 2425 2426 2427 2428
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2429 2430
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2431 2432 2433 2434
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}