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

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

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

30
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
    }

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

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

198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218
        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;


219 220
        switch (message.msgid)
        {
pixhawk's avatar
pixhawk committed
221
        case MAVLINK_MSG_ID_HEARTBEAT:
222
        {
223
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
224
            emit heartbeat(this);
225 226
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
pixhawk's avatar
pixhawk committed
227
            // Set new type if it has changed
228
            if (this->type != state.type)
229
            {
230
                this->type = state.type;
231 232 233 234
                if (airframe == 0)
                {
                    switch (type)
                    {
lm's avatar
lm committed
235
                    case MAV_TYPE_FIXED_WING:
236 237
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
lm's avatar
lm committed
238
                    case MAV_TYPE_QUADROTOR:
239 240
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
241 242 243
                    case MAV_TYPE_HEXAROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
                        break;
244 245 246 247 248
                    default:
                        // Do nothing
                        break;
                    }
                }
249
                this->autopilot = state.autopilot;
pixhawk's avatar
pixhawk committed
250 251
                emit systemTypeSet(this, type);
            }
252

253 254 255 256 257 258 259 260 261 262 263 264 265 266 267
            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();
                }
            }
268

269 270 271 272 273 274
            QString audiostring = "System " + getUASName();
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
275 276


277 278 279 280 281 282 283
            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);
284

285
                shortStateText = uasState;
286

287 288
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
289

290
            if (this->mode != static_cast<int>(state.base_mode))
291 292
            {
                modechanged = true;
293
                this->mode = static_cast<int>(state.base_mode);
294
                shortModeText = getShortModeTextFor(this->mode);
295

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

298 299
                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed
300

301
            if (navMode != state.custom_mode)
302
            {
303 304
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
305 306
                navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
            }
307

308 309 310 311 312 313 314 315 316 317 318
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
319

320 321 322 323 324 325 326
            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();
327
                GAudioOutput::instance()->say(audiostring.toLower());
328
            }
lm's avatar
lm committed
329

330 331 332 333 334
//            if (state.system_status == MAV_STATE_POWEROFF)
//            {
//                emit systemRemoved(this);
//                emit systemRemoved();
//            }
335
}
336

337
            break;
338 339 340 341 342
//        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
//        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
//            // Receive named value message
//            receiveMessageNamedValue(message);
//            break;
343 344
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
345 346 347 348
                if (multiComponentSourceDetected && message.compid != MAV_COMP_ID_IMU_2)
                {
                    break;
                }
349 350
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
351

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

354
                currentVoltage = state.voltage_battery/1000.0f;
LM's avatar
LM committed
355
                lpVoltage = filterVoltage(currentVoltage);
LM's avatar
LM committed
356

LM's avatar
LM committed
357 358
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
359
                if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
360
                {
361
                    chargeLevel = state.battery_remaining;
LM's avatar
LM committed
362 363 364
                }
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
365
                emit voltageChanged(message.sysid, state.voltage_battery/1000);
366

LM's avatar
LM committed
367
                // LOW BATTERY ALARM
368 369
                if (lpVoltage < warnVoltage)
                {
LM's avatar
LM committed
370
                    startLowBattAlarm();
371 372 373
                }
                else
                {
LM's avatar
LM committed
374 375
                    stopLowBattAlarm();
                }
376

LM's avatar
LM committed
377
                // COMMUNICATIONS DROP RATE
378 379
                // FIXME
                emit dropRateChanged(this->getUASID(), state.drop_rate_comm/10000.0f);
380
            }
LM's avatar
LM committed
381
            break;
pixhawk's avatar
pixhawk committed
382
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
383
            {
384 385
                if (wrongComponent) break;

LM's avatar
LM committed
386 387
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
388
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
LM's avatar
LM committed
389
                lastAttitude = time;
LM's avatar
LM committed
390 391 392 393
                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);

394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409
//                // 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
410

411

LM's avatar
LM committed
412
                attitudeKnown = true;
413
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
414
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
415
            }
LM's avatar
LM committed
416
            break;
lm's avatar
lm committed
417 418 419 420
        case MAVLINK_MSG_ID_HIL_CONTROLS:
            {
                mavlink_hil_controls_t hil;
                mavlink_msg_hil_controls_decode(&message, &hil);
421
                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
422 423
            }
            break;
424 425
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
426 427 428 429 430 431
                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);

432 433
                if (!attitudeKnown)
                {
LM's avatar
LM committed
434 435 436
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
437

LM's avatar
LM committed
438
                emit altitudeChanged(uasId, hud.alt);
LM's avatar
LM committed
439
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
LM's avatar
LM committed
440 441
            }
            break;
lm's avatar
lm committed
442
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
lm's avatar
lm committed
443
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
444
            //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
445
            {
lm's avatar
lm committed
446 447
                mavlink_local_position_ned_t pos;
                mavlink_msg_local_position_ned_decode(&message, &pos);
448
                quint64 time = getUnixTime(pos.time_boot_ms);
LM's avatar
LM committed
449 450 451 452 453 454 455 456 457 458 459 460
                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;
461
                isLocalPositionKnown = true;
lm's avatar
lm committed
462
            }
LM's avatar
LM committed
463
            break;
464
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
465 466
            //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
467 468 469 470 471 472 473 474 475 476 477 478 479
            {
                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
480 481
                if (!positionLock)
                {
LM's avatar
LM committed
482 483 484 485
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
486
                isGlobalPositionKnown = true;
LM's avatar
LM committed
487 488
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
489
            }
LM's avatar
LM committed
490
            break;
491 492
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
LM's avatar
LM committed
493 494 495 496 497
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);

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

501 502
                if (pos.fix_type > 2)
                {
LM's avatar
LM committed
503 504 505 506 507
                    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;
508
                    isGlobalPositionKnown = true;
LM's avatar
LM committed
509 510 511

                    // Check for NaN
                    int alt = pos.alt;
512 513
                    if (!isnan(alt) && !isinf(alt))
                    {
LM's avatar
LM committed
514
                        alt = 0;
515
                        //emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE");
LM's avatar
LM committed
516
                    }
lm's avatar
lm committed
517
                    // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
LM's avatar
LM committed
518
                    // Smaller than threshold and not NaN
LM's avatar
LM committed
519 520 521

                    float vel = pos.vel/100.0f;

522 523
                    if (vel < 1000000 && !isnan(vel) && !isinf(vel))
                    {
lm's avatar
lm committed
524
                        // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time);
LM's avatar
LM committed
525 526
                        //qDebug() << "GOT GPS RAW";
                        // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
527 528 529
                    }
                    else
                    {
LM's avatar
LM committed
530
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
LM's avatar
LM committed
531
                    }
lm's avatar
lm committed
532 533
                }
            }
LM's avatar
LM committed
534
            break;
535 536
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
LM's avatar
LM committed
537 538
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
539 540
                for(int i = 0; i < (int)pos.satellites_visible; i++)
                {
LM's avatar
LM committed
541 542
                    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]));
                }
543
            }
LM's avatar
LM committed
544
            break;
545
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
546
            {
547 548
                mavlink_gps_global_origin_t pos;
                mavlink_msg_gps_global_origin_decode(&message, &pos);
LM's avatar
LM committed
549
                emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
LM's avatar
LM committed
550 551
            }
            break;
552 553
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            {
LM's avatar
LM committed
554 555 556 557 558 559 560 561 562 563 564 565 566
                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;
567 568
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
LM's avatar
LM committed
569 570 571 572 573 574 575 576 577 578 579
                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
580
            }
LM's avatar
LM committed
581
            break;
582 583
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
LM's avatar
LM committed
584 585
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
586
                QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
LM's avatar
LM committed
587 588
                QString parameterName = QString(bytes);
                int component = message.compid;
589 590
                mavlink_param_union_t val;
                val.param_float = value.param_value;
591
                val.type = value.param_type;
592

LM's avatar
LM committed
593
                // Insert component if necessary
594 595
                if (!parameters.contains(component))
                {
596
                    parameters.insert(component, new QMap<QString, QVariant>());
LM's avatar
LM committed
597
                }
598

LM's avatar
LM committed
599 600
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
601

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

lm's avatar
lm committed
678
        case MAVLINK_MSG_ID_MISSION_ITEM:
679
            {
lm's avatar
lm committed
680 681
                mavlink_mission_item_t wp;
                mavlink_msg_mission_item_decode(&message, &wp);
LM's avatar
LM committed
682
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
683
                if(wp.target_system == mavlink->getSystemId())
684
                {
LM's avatar
LM committed
685 686
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
LM's avatar
LM committed
687 688 689 690
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
691
            }
LM's avatar
LM committed
692
            break;
pixhawk's avatar
pixhawk committed
693

lm's avatar
lm committed
694
        case MAVLINK_MSG_ID_MISSION_ACK:
695
            {
lm's avatar
lm committed
696 697
                mavlink_mission_ack_t wpa;
                mavlink_msg_mission_ack_decode(&message, &wpa);
698 699
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
700 701
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
702
            }
LM's avatar
LM committed
703
            break;
704

lm's avatar
lm committed
705
        case MAVLINK_MSG_ID_MISSION_REQUEST:
706
            {
lm's avatar
lm committed
707 708
                mavlink_mission_request_t wpr;
                mavlink_msg_mission_request_decode(&message, &wpr);
709
                if(wpr.target_system == mavlink->getSystemId())
710
                {
LM's avatar
LM committed
711 712
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
LM's avatar
LM committed
713 714 715 716
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
717
            }
LM's avatar
LM committed
718
            break;
pixhawk's avatar
pixhawk committed
719

lm's avatar
lm committed
720
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
721
            {
lm's avatar
lm committed
722 723
                mavlink_mission_item_reached_t wpr;
                mavlink_msg_mission_item_reached_decode(&message, &wpr);
LM's avatar
LM committed
724 725 726 727 728 729
                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
730

lm's avatar
lm committed
731
        case MAVLINK_MSG_ID_MISSION_CURRENT:
732
            {
lm's avatar
lm committed
733 734
                mavlink_mission_current_t wpc;
                mavlink_msg_mission_current_decode(&message, &wpc);
LM's avatar
LM committed
735 736 737
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
738

739 740
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
741 742 743 744 745
                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;
746 747
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
748 749
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
lm's avatar
lm committed
750
                mavlink_msg_statustext_get_text(&message, b.data());
LM's avatar
LM committed
751 752 753 754 755 756 757 758
                //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;
759
#ifdef MAVLINK_ENABLED_PIXHAWK
760 761
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
762 763 764 765 766 767 768 769 770 771 772
                qDebug() << "RECIEVED ACK TO GET IMAGE";
                mavlink_data_transmission_handshake_t p;
                mavlink_msg_data_transmission_handshake_decode(&message, &p);
                imageSize = p.size;
                imagePackets = p.packets;
                imagePayload = p.payload;
                imageQuality = p.jpg_quality;
                imageType = p.type;
                imageStart = QGC::groundTimeMilliseconds();
            }
            break;
773

774 775
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
776 777 778 779 780 781 782 783 784 785 786
                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;
787 788
                }

789 790
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
791 792 793 794 795
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
796

LM's avatar
LM committed
797
                ++imagePacketsArrived;
798

LM's avatar
LM committed
799 800 801 802 803 804 805 806
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    imagePacketsArrived = 0;
                    emit imageReady(this);
                    qDebug() << "imageReady emitted. all packets arrived";
                }
807
            }
LM's avatar
LM committed
808
            break;
809
#endif
lm's avatar
lm committed
810 811 812 813 814 815 816 817
//        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;
818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836
        // 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
837
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
838 839 840
//                    break;
//                case 1:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
841
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
842 843 844
//                    break;
//                case 2:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
845
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
846 847 848
//                    break;
//                case 3:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
849
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
850 851 852
//                    break;
//                case 4:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
853
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
854 855 856
//                    break;
//                case 5:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
857
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
858 859 860
//                    break;
//                case 6:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
861
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
862 863 864 865 866
//                    break;
//                }
//            }
//        }
//        break;
lm's avatar
lm committed
867
#ifdef MAVLINK_ENABLED_UALBERTA
868 869
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
LM's avatar
LM committed
870 871 872
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = getUnixTime();
lm's avatar
lm committed
873 874 875 876 877 878
                // 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
879 880
            }
            break;
881 882
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
LM's avatar
LM committed
883 884
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
885 886 887 888 889 890
                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
891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909

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

911
#endif
LM's avatar
LM committed
912
            // Messages to ignore
913
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
lm's avatar
lm committed
914 915 916 917 918 919 920 921
        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
922
        case MAVLINK_MSG_ID_DEBUG:
923 924
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
925
            break;
926 927 928 929
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
930 931 932 933 934 935 936
                    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
937
            }
LM's avatar
LM committed
938
            break;
pixhawk's avatar
pixhawk committed
939 940 941 942
        }
    }
}

943 944 945 946 947 948 949 950 951 952 953 954
#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);
955
        emit pointCloudChanged(this);
956
    }
957 958 959
    else if (message->GetTypeName() == rgbdImage.GetTypeName())
    {
        rgbdImage.CopyFrom(*message);
960
        emit rgbdImageChanged(this);
961
    }
962 963 964 965
}

#endif

966 967
void UAS::setHomePosition(double lat, double lon, double alt)
{
968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000
    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);
    }
1001 1002
}

1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016
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()));


1017 1018
    if (ret == QMessageBox::Yes)
    {
1019 1020 1021 1022 1023 1024 1025 1026
        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);
1027 1028 1029
    }
}

pixhawk's avatar
pixhawk committed
1030 1031
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1032
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1033
    mavlink_message_t msg;
LM's avatar
LM committed
1034
    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
1035
    sendMessage(msg);
1036
#else
lm's avatar
lm committed
1037 1038 1039 1040
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1041
#endif
pixhawk's avatar
pixhawk committed
1042 1043
}

pixhawk's avatar
pixhawk committed
1044 1045
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1046
#ifdef MAVLINK_ENABLED_PIXHAWK
1047
    mavlink_message_t msg;
1048
    mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
1049
    sendMessage(msg);
lm's avatar
lm committed
1050
#else
1051 1052 1053 1054
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1055 1056 1057 1058
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1059
{
1060 1061
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1062
    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);
1063
    sendMessage(msg);
lm's avatar
lm committed
1064 1065
}

1066
void UAS::startDataRecording()
lm's avatar
lm committed
1067
{
1068
    mavlink_message_t msg;
1069
    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);
1070
    sendMessage(msg);
lm's avatar
lm committed
1071 1072 1073 1074
}

void UAS::stopDataRecording()
{
1075
    mavlink_message_t msg;
1076
    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);
1077
    sendMessage(msg);
lm's avatar
lm committed
1078 1079
}

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

void UAS::startGyroscopeCalibration()
{
1090 1091
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1092
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0, 0, 0, 0);
1093
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1094 1095 1096 1097
}

void UAS::startPressureCalibration()
{
1098 1099
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1100
    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);
1101
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1102 1103
}

LM's avatar
LM committed
1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148
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;
    }
}

1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161
/**
 * @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
1162 1163 1164 1165 1166 1167 1168 1169
/**
 * @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!
 */
1170 1171
quint64 UAS::getUnixTime(quint64 time)
{
1172
    quint64 ret = 0;
LM's avatar
LM committed
1173 1174
    if (attitudeStamped)
    {
1175
        ret = lastAttitude;
LM's avatar
LM committed
1176
    }
1177 1178
    if (time == 0)
    {
1179
        ret = QGC::groundTimeMilliseconds();
1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196
    }
    // 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
1197
#ifndef _MSC_VER
1198
    else if (time < 1261440000000000LLU)
1199
#else
LM's avatar
LM committed
1200
        else if (time < 1261440000000000)
1201
#endif
LM's avatar
LM committed
1202 1203
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1204 1205
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1206
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1207
        }
1208
        ret = time/1000 + onboardTimeOffset;
1209 1210 1211
    }
    else
    {
1212 1213
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1214
        ret = time/1000;
1215
    }
1216
    return ret;
1217 1218
}

1219 1220
QList<QString> UAS::getParameterNames(int component)
{
1221 1222
    if (parameters.contains(component))
    {
1223
        return parameters.value(component)->keys();
1224 1225 1226
    }
    else
    {
1227 1228 1229 1230 1231 1232 1233 1234 1235
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1236
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1237
{
LM's avatar
LM committed
1238 1239 1240 1241 1242
    //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
1243 1244 1245 1246 1247
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1248 1249 1250 1251
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1252
            sendMessage(link, message);
1253 1254 1255
        }
        else
        {
1256 1257 1258
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1259 1260 1261
    }
}

1262 1263 1264 1265
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1266

1267 1268 1269 1270
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1271
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1272 1273 1274 1275 1276 1277
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1278
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1279 1280
                        sendMessage(serial, message);
                    }
1281 1282 1283 1284 1285 1286
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1287 1288
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1289
    if(!link) return;
pixhawk's avatar
pixhawk committed
1290 1291 1292
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1293
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1294 1295
    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
1296
    // If link is connected
1297 1298
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1299 1300 1301 1302 1303 1304 1305 1306
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1307
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1308
{
1309
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1310 1311
}

1312 1313
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1314 1315
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
1316 1317
    switch (mode)
    {
lm's avatar
lm committed
1318
    case 0:
1319
        return QString("PREFLIGHT");
1320 1321 1322 1323
        break;
    default:
        return QString("UNKNOWN");
    }
lm's avatar
lm committed
1324 1325 1326 1327 1328 1329 1330 1331 1332
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1333 1334
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1335 1336
}

pixhawk's avatar
pixhawk committed
1337 1338
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1339 1340
    switch (statusCode)
    {
lm's avatar
lm committed
1341
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1342
        uasState = tr("UNINIT");
1343
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1344
        break;
lm's avatar
lm committed
1345
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1346
        uasState = tr("BOOT");
1347
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1348
        break;
lm's avatar
lm committed
1349
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1350
        uasState = tr("CALIBRATING");
1351
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1352
        break;
lm's avatar
lm committed
1353
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1354
        uasState = tr("ACTIVE");
1355
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1356
        break;
lm's avatar
lm committed
1357 1358
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1359
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1360 1361
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1362
        uasState = tr("CRITICAL");
1363
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1364
        break;
lm's avatar
lm committed
1365
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1366
        uasState = tr("EMERGENCY");
1367
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1368
        break;
James Goppert's avatar
James Goppert committed
1369
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1370 1371 1372
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1373

lm's avatar
lm committed
1374
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1375
        uasState = tr("SHUTDOWN");
1376
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1377
        break;
1378

lm's avatar
lm committed
1379
    default:
pixhawk's avatar
pixhawk committed
1380
        uasState = tr("UNKNOWN");
1381
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1382 1383 1384 1385
        break;
    }
}

1386 1387
QImage UAS::getImage()
{
LM's avatar
LM committed
1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434
#ifdef MAVLINK_ENABLED_PIXHAWK

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

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

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

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

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

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

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

    }
    // BMP with header
    else if (imageType == MAVLINK_DATA_STREAM_IMG_BMP ||
             imageType == MAVLINK_DATA_STREAM_IMG_JPEG ||
             imageType == MAVLINK_DATA_STREAM_IMG_PGM ||
             imageType == MAVLINK_DATA_STREAM_IMG_PNG)
    {
       if (!image.loadFromData(imageRecBuffer))
        {
           qDebug() << "Loading data from image buffer failed!";
        }
    }
1435 1436
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1437
    //imageRecBuffer.clear();
1438
    return image;
1439 1440
#else
	return QImage();
LM's avatar
LM committed
1441
#endif
1442

1443 1444 1445 1446
}

void UAS::requestImage()
{
1447
#ifdef MAVLINK_ENABLED_PIXHAWK
1448 1449
    qDebug() << "trying to get an image from the uas...";

1450 1451 1452
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1453 1454 1455 1456
        mavlink_message_t msg;
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 50);
        sendMessage(msg);
    }
1457
#endif
1458
}
pixhawk's avatar
pixhawk committed
1459 1460 1461 1462 1463 1464 1465 1466 1467


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1468
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1469
{
1470 1471
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1472
        return 0;
1473 1474 1475
    }
    else
    {
pixhawk's avatar
pixhawk committed
1476 1477 1478 1479
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1480
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1481 1482 1483 1484
{
    return commStatus;
}

1485 1486 1487
void UAS::requestParameters()
{
    mavlink_message_t msg;
1488
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1489
    sendMessage(msg);
1490 1491
}

1492
void UAS::writeParametersToStorage()
1493
{
1494
    mavlink_message_t msg;
1495
    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
1496
    qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
1497
    sendMessage(msg);
1498 1499 1500 1501
}

void UAS::readParametersFromStorage()
{
1502
    mavlink_message_t msg;
1503
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
1504
    sendMessage(msg);
lm's avatar
lm committed
1505 1506
}

1507
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1508 1509
{
    // Buffers to write data to
1510
    mavlink_message_t msg;
1511
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1512 1513
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1514
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1515 1516
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1517 1518
    // 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
1519 1520
    stream.req_message_rate = 0;
    // Start / stop the message
1521
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1522 1523 1524 1525 1526
    // 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
1527
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1528 1529
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1530 1531
}

1532
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1533 1534 1535
{
    // Buffers to write data to
    mavlink_message_t msg;
1536
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1537
    // Select the message to request from now on
1538
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1539
    // Select the update rate in Hz the message should be send
1540
    stream.req_message_rate = rate;
lm's avatar
lm committed
1541
    // Start / stop the message
1542
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1543 1544 1545 1546 1547
    // 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
1548
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1549 1550
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1551 1552
}

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

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

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

lm's avatar
lm committed
1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641
//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);
//}
1642

1643
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1644 1645 1646 1647 1648
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1649
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1650
    // Select the update rate in Hz the message should be send
1651
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1652
    // Start / stop the message
1653
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1654 1655 1656 1657 1658 1659 1660 1661 1662 1663
    // 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);
}

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

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

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

lm's avatar
lm committed
1730 1731 1732 1733 1734 1735 1736
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1737
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
lm's avatar
lm committed
1738
{
1739 1740
    if (!id.isNull())
    {
1741 1742
        mavlink_message_t msg;
        mavlink_param_set_t p;
1743 1744 1745 1746 1747 1748 1749
        mavlink_param_union_t union_value;

        // Assign correct value based on QVariant
        switch (value.type())
        {
        case QVariant::Int:
            union_value.param_int32 = value.toInt();
1750
            p.param_type = MAVLINK_TYPE_INT32_T;
1751 1752 1753
            break;
        case QVariant::UInt:
            union_value.param_uint32 = value.toUInt();
1754
            p.param_type = MAVLINK_TYPE_UINT32_T;
1755 1756 1757
            break;
        case QMetaType::Float:
            union_value.param_float = value.toFloat();
1758
            p.param_type = MAVLINK_TYPE_FLOAT;
1759 1760 1761 1762 1763 1764 1765
            break;
        default:
            qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
            return;
        }

        p.param_value = union_value.param_float;
1766 1767 1768
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

1769 1770
        qDebug() << "SENT PARAM:" << value;

1771
        // Copy string into buffer, ensuring not to exceed the buffer size
1772 1773
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1774
            // String characters
1775 1776
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1777 1778
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1779 1780 1781 1782 1783
            //        // 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';
            //        }
1784
            // Zero fill
1785 1786
            else
            {
1787 1788
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1789
        }
1790 1791
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1792
    }
1793 1794
}

1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808
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;
}

1809
void UAS::requestParameter(int component, const QString& parameter)
1810
{
1811
    // Request parameter, use parameter name to request it
1812 1813
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
1814 1815 1816 1817 1818 1819 1820 1821
    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
1822 1823 1824 1825
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
1826
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
1827 1828
}

1829 1830 1831 1832
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
1833 1834 1835 1836
    if (airframe == 0)
    {
        switch (systemType)
        {
lm's avatar
lm committed
1837
        case MAV_TYPE_FIXED_WING:
1838 1839
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
lm's avatar
lm committed
1840
        case MAV_TYPE_QUADROTOR:
1841 1842 1843 1844 1845 1846 1847
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1848 1849
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
1850 1851 1852 1853 1854 1855 1856
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
1857 1858
}

lm's avatar
lm committed
1859 1860 1861
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
1862
    mavlink_command_long_t cmd;
1863 1864 1865 1866 1867 1868
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
1869 1870 1871
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
1872 1873
    cmd.target_system = uasId;
    cmd.target_component = 0;
1874
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1875 1876 1877 1878 1879 1880
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
1881
    mavlink_command_long_t cmd;
1882 1883 1884 1885 1886 1887
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1888 1889 1890
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
1891 1892
    cmd.target_system = uasId;
    cmd.target_component = component;
1893
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1894 1895 1896 1897 1898 1899 1900
    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;
1901 1902 1903 1904 1905 1906
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1907 1908 1909
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
1910 1911
    cmd.target_system = uasId;
    cmd.target_component = component;
1912
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
1913 1914 1915
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1916
/**
lm's avatar
lm committed
1917
 * Launches the system
pixhawk's avatar
pixhawk committed
1918 1919 1920 1921
 *
 **/
void UAS::launch()
{
1922
    mavlink_message_t msg;
1923
    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);
1924
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1925 1926 1927 1928 1929 1930
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
1931
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
1932
{
1933
    mavlink_message_t msg;
1934
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
1935
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1936 1937 1938 1939 1940 1941
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
1942
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
1943
{
1944
    mavlink_message_t msg;
1945
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
1946
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960
}

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
1961 1962
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
1963
    {
1964 1965 1966 1967
        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
1968

1969
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
1970 1971 1972
    }
    else
    {
1973 1974
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
1975 1976
}

1977 1978 1979 1980 1981
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1982 1983
void UAS::receiveButton(int buttonIndex)
{
1984 1985
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
1986
    case 0:
pixhawk's avatar
pixhawk committed
1987

pixhawk's avatar
pixhawk committed
1988 1989
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1990

pixhawk's avatar
pixhawk committed
1991 1992 1993 1994 1995
        break;
    default:

        break;
    }
1996
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1997 1998 1999

}

2000

pixhawk's avatar
pixhawk committed
2001 2002
void UAS::halt()
{
2003 2004 2005
    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
2006 2007 2008 2009
}

void UAS::go()
{
2010 2011 2012
    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
2013 2014 2015 2016 2017
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
2018 2019 2020 2021 2022 2023 2024 2025 2026
    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
2027 2028 2029 2030 2031 2032 2033 2034
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2035 2036
    // FIXME MAVLINKV10PORTINGNEEDED
    halt();
pixhawk's avatar
pixhawk committed
2037 2038 2039
}

/**
lm's avatar
lm committed
2040
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2041 2042 2043 2044 2045 2046
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
2047
    halt();
lm's avatar
lm committed
2048 2049 2050 2051 2052 2053 2054 2055 2056 2057 2058 2059 2060 2061 2062 2063 2064 2065 2066 2067 2068 2069 2070 2071 2072 2073
    // 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
2074 2075
}

lm's avatar
lm committed
2076 2077 2078 2079 2080
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2081
        startHil();
lm's avatar
lm committed
2082 2083 2084
    }
    else
    {
2085
        stopHil();
lm's avatar
lm committed
2086 2087 2088 2089 2090 2091 2092 2093 2094 2095 2096 2097 2098 2099 2100 2101 2102 2103 2104 2105 2106 2107 2108 2109 2110 2111 2112 2113 2114 2115 2116
    }
}

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


2117 2118
void UAS::startHil()
{
lm's avatar
lm committed
2119 2120
    // Connect Flight Gear Link
    simulation->connectSimulation();
2121
    mavlink_message_t msg;
LM's avatar
LM committed
2122
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
2123
    sendMessage(msg);
2124 2125
}

2126 2127
void UAS::stopHil()
{
lm's avatar
lm committed
2128
    simulation->disconnectSimulation();
2129
    mavlink_message_t msg;
LM's avatar
LM committed
2130
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
2131
    sendMessage(msg);
2132 2133 2134
}


pixhawk's avatar
pixhawk committed
2135 2136
void UAS::shutdown()
{
2137 2138 2139 2140 2141
    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
2142

2143 2144 2145
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2146

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

2150 2151 2152 2153
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2154
        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);
2155 2156 2157
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2158 2159
}

2160 2161
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2162
    mavlink_message_t msg;
lm's avatar
lm committed
2163
    mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw);
2164
    sendMessage(msg);
2165 2166
}

pixhawk's avatar
pixhawk committed
2167 2168 2169
/**
 * @return The name of this system as string in human-readable form
 */
2170
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2171 2172
{
    QString result;
2173 2174
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2175
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2176 2177 2178
    }
    else
    {
pixhawk's avatar
pixhawk committed
2179 2180 2181 2182 2183
        result = name;
    }
    return result;
}

2184 2185 2186 2187 2188
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2189 2190 2191
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2192 2193 2194
    uint8_t modeid = id;

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

LM's avatar
LM committed
2196
    // BASE MODE DECODING
pixhawk's avatar
pixhawk committed
2197
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
LM's avatar
LM committed
2198
    {
pixhawk's avatar
pixhawk committed
2199
        mode += "AUTO";
LM's avatar
LM committed
2200
    }
pixhawk's avatar
pixhawk committed
2201
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
LM's avatar
LM committed
2202
    {
pixhawk's avatar
pixhawk committed
2203
        mode += "GUIDED";
LM's avatar
LM committed
2204
    }
pixhawk's avatar
pixhawk committed
2205
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
LM's avatar
LM committed
2206
    {
pixhawk's avatar
pixhawk committed
2207
        mode += "STABILIZED";
LM's avatar
LM committed
2208
    }
pixhawk's avatar
pixhawk committed
2209
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
LM's avatar
LM committed
2210
    {
pixhawk's avatar
pixhawk committed
2211
        mode += "TEST";
LM's avatar
LM committed
2212
    }
pixhawk's avatar
pixhawk committed
2213
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
LM's avatar
LM committed
2214
    {
pixhawk's avatar
pixhawk committed
2215
        mode += "MANUAL";
LM's avatar
LM committed
2216
    }
pixhawk's avatar
pixhawk committed
2217 2218

    if (modeid == 0)
LM's avatar
LM committed
2219
    {
2220
        mode = "PREFLIGHT";
LM's avatar
LM committed
2221 2222 2223
    }

    // ARMED STATE DECODING
pixhawk's avatar
pixhawk committed
2224
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
LM's avatar
LM committed
2225 2226 2227 2228 2229 2230 2231 2232 2233
    {
        mode.prepend("A|");
    }
    else
    {
        mode.prepend("D|");
    }

    // HARDWARE IN THE LOOP DECODING
pixhawk's avatar
pixhawk committed
2234
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
LM's avatar
LM committed
2235 2236
    {
        mode.prepend("HIL:");
2237 2238 2239 2240 2241
    }

    return mode;
}

2242 2243 2244 2245 2246
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2247 2248
void UAS::addLink(LinkInterface* link)
{
2249 2250
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2251
        links->append(link);
2252
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2253 2254 2255
    }
}

2256 2257 2258
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2259 2260
    if (link)
    {
2261 2262 2263 2264
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2265 2266 2267 2268 2269 2270 2271 2272 2273 2274 2275 2276 2277 2278 2279
/**
 * @brief Get the links associated with this robot
 *
 **/
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}



void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2280 2281
    switch (batteryType)
    {
lm's avatar
lm committed
2282
    case NICD:
pixhawk's avatar
pixhawk committed
2283
        break;
lm's avatar
lm committed
2284
    case NIMH:
pixhawk's avatar
pixhawk committed
2285
        break;
lm's avatar
lm committed
2286
    case LIION:
pixhawk's avatar
pixhawk committed
2287
        break;
lm's avatar
lm committed
2288
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2289 2290 2291
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2292
    case LIFE:
pixhawk's avatar
pixhawk committed
2293
        break;
lm's avatar
lm committed
2294
    case AGZN:
pixhawk's avatar
pixhawk committed
2295 2296 2297 2298
        break;
    }
}

2299 2300
void UAS::setBatterySpecs(const QString& specs)
{
2301 2302
    if (specs.length() == 0 || specs.contains("%"))
    {
2303
        batteryRemainingEstimateEnabled = false;
2304
        bool ok;
2305 2306 2307
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2308 2309
        if (ok)
        {
2310
            warnLevelPercent = temp;
2311 2312 2313
        }
        else
        {
2314 2315
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2316 2317 2318
    }
    else
    {
2319 2320 2321 2322 2323
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2324 2325
        if (parts.length() == 3)
        {
2326 2327 2328 2329 2330 2331 2332 2333 2334 2335 2336
            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;
2337 2338 2339
        }
        else
        {
2340 2341
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2342 2343 2344 2345 2346
    }
}

QString UAS::getBatterySpecs()
{
2347 2348
    if (batteryRemainingEstimateEnabled)
    {
2349
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2350 2351 2352
    }
    else
    {
2353 2354
        return QString("%1%").arg(warnLevelPercent);
    }
2355 2356
}

pixhawk's avatar
pixhawk committed
2357 2358 2359 2360 2361 2362 2363 2364 2365 2366 2367 2368 2369
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
2370 2371 2372
/**
 * @return charge level in percent - 0 - 100
 */
2373
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2374
{
2375 2376 2377 2378
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2379
            chargeLevel = 0.0f;
2380 2381 2382
        }
        else if (lpVoltage > fullVoltage)
        {
2383
            chargeLevel = 100.0f;
2384 2385 2386
        }
        else
        {
2387 2388
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2389 2390
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2391 2392
}

lm's avatar
lm committed
2393 2394
void UAS::startLowBattAlarm()
{
2395 2396
    if (!lowBattAlarm)
    {
2397
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2398
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2399 2400 2401 2402 2403 2404
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2405 2406
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2407 2408 2409 2410
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}