UAS.cc 83.4 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 168
    if (UASManager::instance()->getActiveUAS() != this)
    {
169 170 171 172 173 174 175 176
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

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

void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
181
    if (!link) return;
182 183
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
184
        addLink(link);
185
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
186 187
    }

LM's avatar
LM committed
188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219
    if (!components.contains(message.compid))
    {
        QString componentName;

        switch (message.compid)
        {
        case MAV_COMP_ID_ALL:
            {
                componentName = "ANONYMOUS";
                break;
            }
        case MAV_COMP_ID_IMU:
            {
                componentName = "IMU #1";
                break;
            }
        case MAV_COMP_ID_CAMERA:
            {
                componentName = "CAMERA";
                break;
            }
        case MAV_COMP_ID_MISSIONPLANNER:
            {
                componentName = "MISSIONPLANNER";
                break;
            }
        }

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

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

LM's avatar
LM committed
222 223 224 225
    // 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))
226
    {
pixhawk's avatar
pixhawk committed
227 228
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
229

230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250
        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;


251 252
        switch (message.msgid)
        {
pixhawk's avatar
pixhawk committed
253
        case MAVLINK_MSG_ID_HEARTBEAT:
254
        {
255
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
256
            emit heartbeat(this);
257 258
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
pixhawk's avatar
pixhawk committed
259
            // Set new type if it has changed
260
            if (this->type != state.type)
261
            {
262
                this->type = state.type;
263 264 265 266
                if (airframe == 0)
                {
                    switch (type)
                    {
lm's avatar
lm committed
267
                    case MAV_TYPE_FIXED_WING:
268 269
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
lm's avatar
lm committed
270
                    case MAV_TYPE_QUADROTOR:
271 272
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
273 274 275
                    case MAV_TYPE_HEXAROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
                        break;
276 277 278 279 280
                    default:
                        // Do nothing
                        break;
                    }
                }
281
                this->autopilot = state.autopilot;
pixhawk's avatar
pixhawk committed
282 283
                emit systemTypeSet(this, type);
            }
284

285 286 287 288 289 290 291 292 293 294 295 296 297 298 299
            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();
                }
            }
300

301 302 303 304 305 306
            QString audiostring = "System " + getUASName();
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
307 308


309 310 311 312 313 314 315
            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);
316

317
                shortStateText = uasState;
318

319 320
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
321

322
            if (this->mode != static_cast<int>(state.base_mode))
323 324
            {
                modechanged = true;
325
                this->mode = static_cast<int>(state.base_mode);
326
                shortModeText = getShortModeTextFor(this->mode);
327

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

330 331
                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed
332

333
            if (navMode != state.custom_mode)
334
            {
335 336
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
337 338
                navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
            }
339

340 341 342 343 344 345 346 347 348 349 350
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
351

352 353 354 355 356 357 358
            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();
359
                GAudioOutput::instance()->say(audiostring.toLower());
360
            }
lm's avatar
lm committed
361

362 363 364 365 366
//            if (state.system_status == MAV_STATE_POWEROFF)
//            {
//                emit systemRemoved(this);
//                emit systemRemoved();
//            }
367
}
368

369
            break;
370 371 372 373 374
//        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
//        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
//            // Receive named value message
//            receiveMessageNamedValue(message);
//            break;
375 376
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
377 378 379 380
                if (multiComponentSourceDetected && message.compid != MAV_COMP_ID_IMU_2)
                {
                    break;
                }
381 382
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
383

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

386
                currentVoltage = state.voltage_battery/1000.0f;
LM's avatar
LM committed
387
                lpVoltage = filterVoltage(currentVoltage);
LM's avatar
LM committed
388

LM's avatar
LM committed
389 390
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
391
                if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
392
                {
393
                    chargeLevel = state.battery_remaining;
LM's avatar
LM committed
394 395 396
                }
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
397
                emit voltageChanged(message.sysid, state.voltage_battery/1000);
398

LM's avatar
LM committed
399
                // LOW BATTERY ALARM
400 401
                if (lpVoltage < warnVoltage)
                {
LM's avatar
LM committed
402
                    startLowBattAlarm();
403 404 405
                }
                else
                {
LM's avatar
LM committed
406 407
                    stopLowBattAlarm();
                }
408

LM's avatar
LM committed
409
                // COMMUNICATIONS DROP RATE
410 411
                // FIXME
                emit dropRateChanged(this->getUASID(), state.drop_rate_comm/10000.0f);
412
            }
LM's avatar
LM committed
413
            break;
pixhawk's avatar
pixhawk committed
414
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
415
            {
416 417
                if (wrongComponent) break;

LM's avatar
LM committed
418 419
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
420
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
LM's avatar
LM committed
421
                lastAttitude = time;
LM's avatar
LM committed
422 423 424 425
                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);

426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441
//                // 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
442

443

LM's avatar
LM committed
444
                attitudeKnown = true;
445
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
446
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
447
            }
LM's avatar
LM committed
448
            break;
lm's avatar
lm committed
449 450 451 452
        case MAVLINK_MSG_ID_HIL_CONTROLS:
            {
                mavlink_hil_controls_t hil;
                mavlink_msg_hil_controls_decode(&message, &hil);
453
                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
454 455
            }
            break;
456 457
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
458 459 460 461 462 463
                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);

464 465
                if (!attitudeKnown)
                {
LM's avatar
LM committed
466 467 468
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
469

LM's avatar
LM committed
470
                emit altitudeChanged(uasId, hud.alt);
LM's avatar
LM committed
471
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
LM's avatar
LM committed
472 473
            }
            break;
lm's avatar
lm committed
474
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
lm's avatar
lm committed
475
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
476
            //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
477
            {
lm's avatar
lm committed
478 479
                mavlink_local_position_ned_t pos;
                mavlink_msg_local_position_ned_decode(&message, &pos);
480
                quint64 time = getUnixTime(pos.time_boot_ms);
LM's avatar
LM committed
481 482 483 484 485 486 487 488 489 490 491 492
                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;
493
                isLocalPositionKnown = true;
lm's avatar
lm committed
494
            }
LM's avatar
LM committed
495
            break;
496
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
497 498
            //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
499 500 501 502 503 504 505 506 507 508 509 510 511
            {
                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
512 513
                if (!positionLock)
                {
LM's avatar
LM committed
514 515 516 517
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
518
                isGlobalPositionKnown = true;
LM's avatar
LM committed
519 520
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
521
            }
LM's avatar
LM committed
522
            break;
523 524
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
LM's avatar
LM committed
525 526 527 528 529
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);

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

533 534
                if (pos.fix_type > 2)
                {
LM's avatar
LM committed
535 536 537 538 539
                    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;
540
                    isGlobalPositionKnown = true;
LM's avatar
LM committed
541 542 543

                    // Check for NaN
                    int alt = pos.alt;
544 545
                    if (!isnan(alt) && !isinf(alt))
                    {
LM's avatar
LM committed
546
                        alt = 0;
547
                        //emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE");
LM's avatar
LM committed
548
                    }
lm's avatar
lm committed
549
                    // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
LM's avatar
LM committed
550
                    // Smaller than threshold and not NaN
LM's avatar
LM committed
551 552 553

                    float vel = pos.vel/100.0f;

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

LM's avatar
LM committed
625
                // Insert component if necessary
626 627
                if (!parameters.contains(component))
                {
628
                    parameters.insert(component, new QMap<QString, QVariant>());
LM's avatar
LM committed
629
                }
630

LM's avatar
LM committed
631 632
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
633

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

lm's avatar
lm committed
710
        case MAVLINK_MSG_ID_MISSION_ITEM:
711
            {
lm's avatar
lm committed
712 713
                mavlink_mission_item_t wp;
                mavlink_msg_mission_item_decode(&message, &wp);
LM's avatar
LM committed
714
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
715
                if(wp.target_system == mavlink->getSystemId())
716
                {
LM's avatar
LM committed
717 718
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
LM's avatar
LM committed
719 720 721 722
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
723
            }
LM's avatar
LM committed
724
            break;
pixhawk's avatar
pixhawk committed
725

lm's avatar
lm committed
726
        case MAVLINK_MSG_ID_MISSION_ACK:
727
            {
lm's avatar
lm committed
728 729
                mavlink_mission_ack_t wpa;
                mavlink_msg_mission_ack_decode(&message, &wpa);
730 731
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
732 733
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
734
            }
LM's avatar
LM committed
735
            break;
736

lm's avatar
lm committed
737
        case MAVLINK_MSG_ID_MISSION_REQUEST:
738
            {
lm's avatar
lm committed
739 740
                mavlink_mission_request_t wpr;
                mavlink_msg_mission_request_decode(&message, &wpr);
741
                if(wpr.target_system == mavlink->getSystemId())
742
                {
LM's avatar
LM committed
743 744
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
LM's avatar
LM committed
745 746 747 748
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
749
            }
LM's avatar
LM committed
750
            break;
pixhawk's avatar
pixhawk committed
751

lm's avatar
lm committed
752
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
753
            {
lm's avatar
lm committed
754 755
                mavlink_mission_item_reached_t wpr;
                mavlink_msg_mission_item_reached_decode(&message, &wpr);
LM's avatar
LM committed
756 757 758 759 760 761
                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
762

lm's avatar
lm committed
763
        case MAVLINK_MSG_ID_MISSION_CURRENT:
764
            {
lm's avatar
lm committed
765 766
                mavlink_mission_current_t wpc;
                mavlink_msg_mission_current_decode(&message, &wpc);
LM's avatar
LM committed
767 768 769
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
770

771 772
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
773 774 775 776 777
                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;
778 779
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
780 781
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
lm's avatar
lm committed
782
                mavlink_msg_statustext_get_text(&message, b.data());
LM's avatar
LM committed
783 784 785 786 787 788 789 790
                //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;
791
#ifdef MAVLINK_ENABLED_PIXHAWK
792 793
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
794 795 796 797 798 799 800 801
                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;
LM's avatar
LM committed
802 803
                imageWidth = p.width;
                imageHeight = p.height;
LM's avatar
LM committed
804 805 806
                imageStart = QGC::groundTimeMilliseconds();
            }
            break;
807

808 809
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
810 811 812 813 814 815 816 817 818 819 820
                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;
821 822
                }

823 824
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
825 826 827 828 829
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
830

LM's avatar
LM committed
831
                ++imagePacketsArrived;
832

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

                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;
944

945
#endif
LM's avatar
LM committed
946
            // Messages to ignore
947
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
lm's avatar
lm committed
948 949 950 951 952 953 954 955
        case MAVLINK_MSG_ID_RAW_IMU:
        case MAVLINK_MSG_ID_SCALED_IMU:
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
        case MAVLINK_MSG_ID_RAW_PRESSURE:
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
        case MAVLINK_MSG_ID_OPTICAL_FLOW:
        case MAVLINK_MSG_ID_DEBUG_VECT:
LM's avatar
LM committed
956
        case MAVLINK_MSG_ID_DEBUG:
957 958
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
959
            break;
960 961 962 963
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
964 965 966 967 968 969 970
                    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
971
            }
LM's avatar
LM committed
972
            break;
pixhawk's avatar
pixhawk committed
973 974 975 976
        }
    }
}

977 978 979 980 981 982 983 984 985 986 987 988
#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);
989
        emit pointCloudChanged(this);
990
    }
991 992 993
    else if (message->GetTypeName() == rgbdImage.GetTypeName())
    {
        rgbdImage.CopyFrom(*message);
994
        emit rgbdImageChanged(this);
995
    }
996 997 998 999
}

#endif

1000 1001
void UAS::setHomePosition(double lat, double lon, double alt)
{
1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034
    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);
    }
1035 1036
}

1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050
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()));


1051 1052
    if (ret == QMessageBox::Yes)
    {
1053 1054 1055 1056 1057 1058 1059 1060
        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);
1061 1062 1063
    }
}

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

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

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

1100
void UAS::startDataRecording()
lm's avatar
lm committed
1101
{
1102
    mavlink_message_t msg;
1103
    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);
1104
    sendMessage(msg);
lm's avatar
lm committed
1105 1106 1107 1108
}

void UAS::stopDataRecording()
{
1109
    mavlink_message_t msg;
1110
    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);
1111
    sendMessage(msg);
lm's avatar
lm committed
1112 1113
}

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

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

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

LM's avatar
LM committed
1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182
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;
    }
}

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

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

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

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

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

1296 1297 1298 1299
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1300

1301 1302 1303 1304
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1305
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1306 1307 1308 1309 1310 1311
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1312
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1313 1314
                        sendMessage(serial, message);
                    }
1315 1316 1317 1318 1319 1320
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1321 1322
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1323
    if(!link) return;
pixhawk's avatar
pixhawk committed
1324 1325 1326
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1327
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1328 1329
    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
1330
    // If link is connected
1331 1332
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1333 1334 1335 1336 1337 1338 1339 1340
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1341
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1342
{
1343
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1344 1345
}

1346 1347
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1348 1349
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
1350 1351
    switch (mode)
    {
lm's avatar
lm committed
1352
    case 0:
1353
        return QString("PREFLIGHT");
1354 1355 1356 1357
        break;
    default:
        return QString("UNKNOWN");
    }
lm's avatar
lm committed
1358 1359 1360 1361 1362 1363 1364 1365 1366
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1367 1368
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1369 1370
}

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

lm's avatar
lm committed
1408
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1409
        uasState = tr("SHUTDOWN");
1410
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1411
        break;
1412

lm's avatar
lm committed
1413
    default:
pixhawk's avatar
pixhawk committed
1414
        uasState = tr("UNKNOWN");
1415
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1416 1417 1418 1419
        break;
    }
}

1420 1421
QImage UAS::getImage()
{
LM's avatar
LM committed
1422 1423 1424 1425 1426 1427 1428
#ifdef MAVLINK_ENABLED_PIXHAWK

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

    // RAW greyscale
    if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
    {
LM's avatar
LM committed
1429 1430
        // TODO FIXME
        int imgColors = 255;//imageSize/(imageWidth*imageHeight);
LM's avatar
LM committed
1431 1432 1433 1434
        //const int headerSize = 15;

        // Construct PGM header
        QString header("P5\n%1 %2\n%3\n");
LM's avatar
LM committed
1435
        header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
LM's avatar
LM committed
1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465

        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!";
        }
    }
1466 1467
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1468
    //imageRecBuffer.clear();
1469
    return image;
1470 1471
#else
	return QImage();
LM's avatar
LM committed
1472
#endif
1473

1474 1475 1476 1477
}

void UAS::requestImage()
{
1478
#ifdef MAVLINK_ENABLED_PIXHAWK
1479 1480
    qDebug() << "trying to get an image from the uas...";

1481 1482 1483
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1484
        mavlink_message_t msg;
LM's avatar
LM committed
1485
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50);
1486 1487
        sendMessage(msg);
    }
1488
#endif
1489
}
pixhawk's avatar
pixhawk committed
1490 1491 1492 1493 1494 1495 1496 1497 1498


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1499
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1500
{
1501 1502
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1503
        return 0;
1504 1505 1506
    }
    else
    {
pixhawk's avatar
pixhawk committed
1507 1508 1509 1510
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1511
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1512 1513 1514 1515
{
    return commStatus;
}

1516 1517 1518
void UAS::requestParameters()
{
    mavlink_message_t msg;
1519
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1520
    sendMessage(msg);
1521 1522
}

1523
void UAS::writeParametersToStorage()
1524
{
1525
    mavlink_message_t msg;
1526
    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
1527
    qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
1528
    sendMessage(msg);
1529 1530 1531 1532
}

void UAS::readParametersFromStorage()
{
1533
    mavlink_message_t msg;
1534
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
1535
    sendMessage(msg);
lm's avatar
lm committed
1536 1537
}

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

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

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

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

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

lm's avatar
lm committed
1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672
//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);
//}
1673

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

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

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

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

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

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

        p.param_value = union_value.param_float;
1797 1798 1799
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

1800 1801
        qDebug() << "SENT PARAM:" << value;

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

1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839
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;
}

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

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

1879 1880
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
1881 1882 1883 1884 1885 1886 1887
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
1888 1889
}

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

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
1912
    mavlink_command_long_t cmd;
1913 1914 1915 1916 1917 1918
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1919 1920 1921
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
1922 1923
    cmd.target_system = uasId;
    cmd.target_component = component;
1924
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1925 1926 1927 1928 1929 1930 1931
    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;
1932 1933 1934 1935 1936 1937
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1938 1939 1940
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
1941 1942
    cmd.target_system = uasId;
    cmd.target_component = component;
1943
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
1944 1945 1946
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1947
/**
lm's avatar
lm committed
1948
 * Launches the system
pixhawk's avatar
pixhawk committed
1949 1950 1951 1952
 *
 **/
void UAS::launch()
{
1953
    mavlink_message_t msg;
1954
    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);
1955
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1956 1957 1958 1959 1960 1961
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
1962
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
1963
{
1964
    mavlink_message_t msg;
1965
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
1966
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1967 1968 1969 1970 1971 1972
}

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

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
1992 1993
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
1994
    {
1995 1996 1997 1998
        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
1999

2000
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
2001 2002 2003
    }
    else
    {
2004 2005
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2006 2007
}

2008 2009 2010 2011 2012
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2013 2014
void UAS::receiveButton(int buttonIndex)
{
2015 2016
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2017
    case 0:
pixhawk's avatar
pixhawk committed
2018

pixhawk's avatar
pixhawk committed
2019 2020
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2021

pixhawk's avatar
pixhawk committed
2022 2023 2024 2025 2026
        break;
    default:

        break;
    }
2027
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2028 2029 2030

}

2031

pixhawk's avatar
pixhawk committed
2032 2033
void UAS::halt()
{
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_HOLD, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2037 2038 2039 2040
}

void UAS::go()
{
2041 2042 2043
    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
2044 2045 2046 2047 2048
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
2049 2050 2051 2052 2053 2054 2055 2056 2057
    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
2058 2059 2060 2061 2062 2063 2064 2065
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2066 2067
    // FIXME MAVLINKV10PORTINGNEEDED
    halt();
pixhawk's avatar
pixhawk committed
2068 2069 2070
}

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

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

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


2148 2149
void UAS::startHil()
{
lm's avatar
lm committed
2150 2151
    // Connect Flight Gear Link
    simulation->connectSimulation();
2152
    mavlink_message_t msg;
LM's avatar
LM committed
2153
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
2154
    sendMessage(msg);
2155 2156
}

2157 2158
void UAS::stopHil()
{
lm's avatar
lm committed
2159
    simulation->disconnectSimulation();
2160
    mavlink_message_t msg;
LM's avatar
LM committed
2161
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
2162
    sendMessage(msg);
2163 2164 2165
}


pixhawk's avatar
pixhawk committed
2166 2167
void UAS::shutdown()
{
2168 2169 2170 2171 2172
    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
2173

2174 2175 2176
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2177

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

2181 2182 2183 2184
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2185
        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);
2186 2187 2188
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2189 2190
}

2191 2192
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2193
    mavlink_message_t msg;
lm's avatar
lm committed
2194
    mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw);
2195
    sendMessage(msg);
2196 2197
}

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

2215 2216 2217 2218 2219
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2220 2221 2222
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2223 2224 2225
    uint8_t modeid = id;

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

LM's avatar
LM committed
2227
    // BASE MODE DECODING
pixhawk's avatar
pixhawk committed
2228
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
LM's avatar
LM committed
2229
    {
pixhawk's avatar
pixhawk committed
2230
        mode += "AUTO";
LM's avatar
LM committed
2231
    }
pixhawk's avatar
pixhawk committed
2232
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
LM's avatar
LM committed
2233
    {
pixhawk's avatar
pixhawk committed
2234
        mode += "GUIDED";
LM's avatar
LM committed
2235
    }
pixhawk's avatar
pixhawk committed
2236
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
LM's avatar
LM committed
2237
    {
pixhawk's avatar
pixhawk committed
2238
        mode += "STABILIZED";
LM's avatar
LM committed
2239
    }
pixhawk's avatar
pixhawk committed
2240
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
LM's avatar
LM committed
2241
    {
pixhawk's avatar
pixhawk committed
2242
        mode += "TEST";
LM's avatar
LM committed
2243
    }
pixhawk's avatar
pixhawk committed
2244
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
LM's avatar
LM committed
2245
    {
pixhawk's avatar
pixhawk committed
2246
        mode += "MANUAL";
LM's avatar
LM committed
2247
    }
pixhawk's avatar
pixhawk committed
2248 2249

    if (modeid == 0)
LM's avatar
LM committed
2250
    {
2251
        mode = "PREFLIGHT";
LM's avatar
LM committed
2252 2253 2254
    }

    // ARMED STATE DECODING
pixhawk's avatar
pixhawk committed
2255
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
LM's avatar
LM committed
2256 2257 2258 2259 2260 2261 2262 2263 2264
    {
        mode.prepend("A|");
    }
    else
    {
        mode.prepend("D|");
    }

    // HARDWARE IN THE LOOP DECODING
pixhawk's avatar
pixhawk committed
2265
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
LM's avatar
LM committed
2266 2267
    {
        mode.prepend("HIL:");
2268 2269 2270 2271 2272
    }

    return mode;
}

2273 2274 2275 2276 2277
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2278 2279
void UAS::addLink(LinkInterface* link)
{
2280 2281
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2282
        links->append(link);
2283
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2284 2285 2286
    }
}

2287 2288 2289
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2290 2291
    if (link)
    {
2292 2293 2294 2295
        links->removeAt(links->indexOf(link));
    }
}

LM's avatar
LM committed
2296

pixhawk's avatar
pixhawk committed
2297 2298 2299 2300 2301
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}

LM's avatar
LM committed
2302 2303 2304 2305 2306
QMap<int, QString> UAS::getComponents()
{
    return components;
}

pixhawk's avatar
pixhawk committed
2307 2308 2309 2310 2311 2312


void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2313 2314
    switch (batteryType)
    {
lm's avatar
lm committed
2315
    case NICD:
pixhawk's avatar
pixhawk committed
2316
        break;
lm's avatar
lm committed
2317
    case NIMH:
pixhawk's avatar
pixhawk committed
2318
        break;
lm's avatar
lm committed
2319
    case LIION:
pixhawk's avatar
pixhawk committed
2320
        break;
lm's avatar
lm committed
2321
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2322 2323 2324
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2325
    case LIFE:
pixhawk's avatar
pixhawk committed
2326
        break;
lm's avatar
lm committed
2327
    case AGZN:
pixhawk's avatar
pixhawk committed
2328 2329 2330 2331
        break;
    }
}

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

QString UAS::getBatterySpecs()
{
2380 2381
    if (batteryRemainingEstimateEnabled)
    {
2382
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2383 2384 2385
    }
    else
    {
2386 2387
        return QString("%1%").arg(warnLevelPercent);
    }
2388 2389
}

pixhawk's avatar
pixhawk committed
2390 2391 2392 2393 2394 2395 2396 2397 2398 2399 2400 2401 2402
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
2403 2404 2405
/**
 * @return charge level in percent - 0 - 100
 */
2406
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2407
{
2408 2409 2410 2411
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2412
            chargeLevel = 0.0f;
2413 2414 2415
        }
        else if (lpVoltage > fullVoltage)
        {
2416
            chargeLevel = 100.0f;
2417 2418 2419
        }
        else
        {
2420 2421
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2422 2423
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2424 2425
}

lm's avatar
lm committed
2426 2427
void UAS::startLowBattAlarm()
{
2428 2429
    if (!lowBattAlarm)
    {
2430
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2431
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2432 2433 2434 2435 2436 2437
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2438 2439
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2440 2441 2442 2443
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}