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

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

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

30 31 32 33
#ifdef QGC_PROTOBUF_ENABLED
#include <google/protobuf/descriptor.h>
#endif

34
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lm's avatar
lm committed
35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77
    uasId(id),
    startTime(QGC::groundTimeMilliseconds()),
    commStatus(COMM_DISCONNECTED),
    name(""),
    autopilot(-1),
    links(new QList<LinkInterface*>()),
    unknownPackets(),
    mavlink(protocol),
    waypointManager(this),
    thrustSum(0),
    thrustMax(10),
    startVoltage(0),
    warnVoltage(9.5f),
    warnLevelPercent(20.0f),
    currentVoltage(12.0f),
    lpVoltage(12.0f),
    batteryRemainingEstimateEnabled(true),
    mode(-1),
    status(-1),
    navMode(-1),
    onboardTimeOffset(0),
    controlRollManual(true),
    controlPitchManual(true),
    controlYawManual(true),
    controlThrustManual(true),
    manualRollAngle(0),
    manualPitchAngle(0),
    manualYawAngle(0),
    manualThrust(0),
    receiveDropRate(0),
    sendDropRate(0),
    lowBattAlarm(false),
    positionLock(false),
    localX(0.0),
    localY(0.0),
    localZ(0.0),
    latitude(0.0),
    longitude(0.0),
    altitude(0.0),
    roll(0.0),
    pitch(0.0),
    yaw(0.0),
    statusTimeout(new QTimer(this)),
78 79 80 81 82 83
#ifdef QGC_PROTOBUF_ENABLED
    receivedPointCloudTimestamp(0.0),
    receivedRGBDImageTimestamp(0.0),
    receivedObstacleListTimestamp(0.0),
    receivedPathTimestamp(0.0),
#endif
lm's avatar
lm committed
84 85 86 87 88 89 90 91 92 93
    paramsOnceRequested(false),
    airframe(QGC_AIRFRAME_EASYSTAR),
    attitudeKnown(false),
    paramManager(NULL),
    attitudeStamped(false),
    lastAttitude(0),
    simulation(new QGCFlightGearLink(this)),
    isLocalPositionKnown(false),
    isGlobalPositionKnown(false),
    systemIsArmed(false)
pixhawk's avatar
pixhawk committed
94
{
95 96 97 98 99 100
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
    }

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

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

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

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

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

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

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

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

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

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

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

LM's avatar
LM committed
198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229
    if (!components.contains(message.compid))
    {
        QString componentName;

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

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

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

LM's avatar
LM committed
232 233 234 235
    // Only accept messages from this system (condition 1)
    // and only then if a) attitudeStamped is disabled OR b) attitudeStamped is enabled
    // and we already got one attitude packet
    if (message.sysid == uasId && (!attitudeStamped || (attitudeStamped && (lastAttitude != 0)) || message.msgid == MAVLINK_MSG_ID_ATTITUDE))
236
    {
pixhawk's avatar
pixhawk committed
237 238
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
239

240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260
        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;


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

295 296 297 298 299 300 301 302 303 304 305 306 307 308 309
            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();
                }
            }
310

311 312 313 314 315 316
            QString audiostring = "System " + getUASName();
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
317 318


319 320 321 322 323 324 325
            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);
326

327
                shortStateText = uasState;
328

329 330
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
331

332
            if (this->mode != static_cast<int>(state.base_mode))
333 334
            {
                modechanged = true;
335
                this->mode = static_cast<int>(state.base_mode);
336
                shortModeText = getShortModeTextFor(this->mode);
337

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

340 341
                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed
342

343
            if (navMode != state.custom_mode)
344
            {
345 346
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
347 348
                navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
            }
349

350 351 352 353 354 355 356 357 358 359 360
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
361

362 363 364 365 366 367 368
            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();
369
                GAudioOutput::instance()->say(audiostring.toLower());
370
            }
lm's avatar
lm committed
371

372 373 374 375 376
//            if (state.system_status == MAV_STATE_POWEROFF)
//            {
//                emit systemRemoved(this);
//                emit systemRemoved();
//            }
377
}
378

379
            break;
380 381 382 383 384
//        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
//        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
//            // Receive named value message
//            receiveMessageNamedValue(message);
//            break;
385 386
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
387 388 389 390
                if (multiComponentSourceDetected && message.compid != MAV_COMP_ID_IMU_2)
                {
                    break;
                }
391 392
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
393

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

396
                currentVoltage = state.voltage_battery/1000.0f;
LM's avatar
LM committed
397
                lpVoltage = filterVoltage(currentVoltage);
LM's avatar
LM committed
398

LM's avatar
LM committed
399 400
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
401
                if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
402
                {
403
                    chargeLevel = state.battery_remaining;
LM's avatar
LM committed
404 405 406
                }
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
407
                emit voltageChanged(message.sysid, state.voltage_battery/1000);
408

LM's avatar
LM committed
409
                // LOW BATTERY ALARM
410 411
                if (lpVoltage < warnVoltage)
                {
LM's avatar
LM committed
412
                    startLowBattAlarm();
413 414 415
                }
                else
                {
LM's avatar
LM committed
416 417
                    stopLowBattAlarm();
                }
418

LM's avatar
LM committed
419
                // COMMUNICATIONS DROP RATE
420 421
                // FIXME
                emit dropRateChanged(this->getUASID(), state.drop_rate_comm/10000.0f);
422
            }
LM's avatar
LM committed
423
            break;
pixhawk's avatar
pixhawk committed
424
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
425
            {
426 427
                if (wrongComponent) break;

LM's avatar
LM committed
428 429
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
430
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
LM's avatar
LM committed
431
                lastAttitude = time;
LM's avatar
LM committed
432 433 434 435
                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);

436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451
//                // 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
452

453

LM's avatar
LM committed
454
                attitudeKnown = true;
455
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
456
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
457
            }
LM's avatar
LM committed
458
            break;
lm's avatar
lm committed
459 460 461 462
        case MAVLINK_MSG_ID_HIL_CONTROLS:
            {
                mavlink_hil_controls_t hil;
                mavlink_msg_hil_controls_decode(&message, &hil);
463
                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
464 465
            }
            break;
466 467
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
468 469 470 471 472 473
                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);

474 475
                if (!attitudeKnown)
                {
LM's avatar
LM committed
476 477 478
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
479

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

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

543 544
                if (pos.fix_type > 2)
                {
LM's avatar
LM committed
545 546 547 548 549
                    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;
550
                    isGlobalPositionKnown = true;
LM's avatar
LM committed
551 552 553

                    // Check for NaN
                    int alt = pos.alt;
554 555
                    if (!isnan(alt) && !isinf(alt))
                    {
LM's avatar
LM committed
556
                        alt = 0;
557
                        //emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE");
LM's avatar
LM committed
558
                    }
lm's avatar
lm committed
559
                    // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
LM's avatar
LM committed
560
                    // Smaller than threshold and not NaN
LM's avatar
LM committed
561 562 563

                    float vel = pos.vel/100.0f;

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

LM's avatar
LM committed
635
                // Insert component if necessary
636 637
                if (!parameters.contains(component))
                {
638
                    parameters.insert(component, new QMap<QString, QVariant>());
LM's avatar
LM committed
639
                }
640

LM's avatar
LM committed
641 642
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
643

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

lm's avatar
lm committed
736
        case MAVLINK_MSG_ID_MISSION_ACK:
737
            {
lm's avatar
lm committed
738 739
                mavlink_mission_ack_t wpa;
                mavlink_msg_mission_ack_decode(&message, &wpa);
740 741
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
742 743
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
744
            }
LM's avatar
LM committed
745
            break;
746

lm's avatar
lm committed
747
        case MAVLINK_MSG_ID_MISSION_REQUEST:
748
            {
lm's avatar
lm committed
749 750
                mavlink_mission_request_t wpr;
                mavlink_msg_mission_request_decode(&message, &wpr);
751
                if(wpr.target_system == mavlink->getSystemId())
752
                {
LM's avatar
LM committed
753 754
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
LM's avatar
LM committed
755 756 757 758
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
759
            }
LM's avatar
LM committed
760
            break;
pixhawk's avatar
pixhawk committed
761

lm's avatar
lm committed
762
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
763
            {
lm's avatar
lm committed
764 765
                mavlink_mission_item_reached_t wpr;
                mavlink_msg_mission_item_reached_decode(&message, &wpr);
LM's avatar
LM committed
766 767 768 769 770 771
                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
772

lm's avatar
lm committed
773
        case MAVLINK_MSG_ID_MISSION_CURRENT:
774
            {
lm's avatar
lm committed
775 776
                mavlink_mission_current_t wpc;
                mavlink_msg_mission_current_decode(&message, &wpc);
LM's avatar
LM committed
777 778 779
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
780

781 782
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
783 784 785 786 787
                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;
788 789
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
790 791
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
lm's avatar
lm committed
792
                mavlink_msg_statustext_get_text(&message, b.data());
LM's avatar
LM committed
793 794 795 796 797 798 799 800
                //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;
801
#ifdef MAVLINK_ENABLED_PIXHAWK
802 803
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
804 805 806 807 808 809 810 811
                qDebug() << "RECIEVED ACK TO GET IMAGE";
                mavlink_data_transmission_handshake_t p;
                mavlink_msg_data_transmission_handshake_decode(&message, &p);
                imageSize = p.size;
                imagePackets = p.packets;
                imagePayload = p.payload;
                imageQuality = p.jpg_quality;
                imageType = p.type;
LM's avatar
LM committed
812 813
                imageWidth = p.width;
                imageHeight = p.height;
LM's avatar
LM committed
814 815 816
                imageStart = QGC::groundTimeMilliseconds();
            }
            break;
817

818 819
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
820 821 822 823 824 825 826 827 828 829 830
                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;
831 832
                }

833 834
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
835 836 837 838 839
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
840

LM's avatar
LM committed
841
                ++imagePacketsArrived;
842

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

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

955
#endif
LM's avatar
LM committed
956
            // Messages to ignore
957
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
lm's avatar
lm committed
958 959 960 961 962 963 964 965
        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
966
        case MAVLINK_MSG_ID_DEBUG:
967 968
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
969
            break;
970 971 972 973
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
974 975 976 977 978 979 980
                    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
981
            }
LM's avatar
LM committed
982
            break;
pixhawk's avatar
pixhawk committed
983 984 985 986
        }
    }
}

987 988 989 990 991 992 993 994 995
#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);
    }

996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030
    const google::protobuf::Descriptor* descriptor = message->GetDescriptor();
    if (!descriptor)
    {
        return;
    }

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

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

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

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

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

    if (source_sysid != uasId)
    {
        return;
    }

1031 1032
    if (message->GetTypeName() == pointCloud.GetTypeName())
    {
1033
        receivedPointCloudTimestamp = QGC::groundTimeSeconds();
1034
        pointCloud.CopyFrom(*message);
1035
        emit pointCloudChanged(this);
1036
    }
1037 1038
    else if (message->GetTypeName() == rgbdImage.GetTypeName())
    {
1039
        receivedRGBDImageTimestamp = QGC::groundTimeSeconds();
1040
        rgbdImage.CopyFrom(*message);
1041
        emit rgbdImageChanged(this);
1042
    }
1043 1044
    else if (message->GetTypeName() == obstacleList.GetTypeName())
    {
1045
        receivedObstacleListTimestamp = QGC::groundTimeSeconds();
1046 1047 1048
        obstacleList.CopyFrom(*message);
        emit obstacleListChanged(this);
    }
1049 1050
    else if (message->GetTypeName() == path.GetTypeName())
    {
1051
        receivedPathTimestamp = QGC::groundTimeSeconds();
1052 1053 1054
        path.CopyFrom(*message);
        emit pathChanged(this);
    }
1055 1056 1057 1058
}

#endif

1059 1060
void UAS::setHomePosition(double lat, double lon, double alt)
{
1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093
    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);
    }
1094 1095
}

1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109
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()));


1110 1111
    if (ret == QMessageBox::Yes)
    {
1112 1113 1114 1115 1116 1117 1118 1119
        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);
1120 1121 1122
    }
}

pixhawk's avatar
pixhawk committed
1123 1124
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1125
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1126
    mavlink_message_t msg;
LM's avatar
LM committed
1127
    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
1128
    sendMessage(msg);
1129
#else
lm's avatar
lm committed
1130 1131 1132 1133
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1134
#endif
pixhawk's avatar
pixhawk committed
1135 1136
}

pixhawk's avatar
pixhawk committed
1137 1138
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1139
#ifdef MAVLINK_ENABLED_PIXHAWK
1140
    mavlink_message_t msg;
1141
    mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
1142
    sendMessage(msg);
lm's avatar
lm committed
1143
#else
1144 1145 1146 1147
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1148 1149 1150 1151
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1152
{
1153 1154
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1155
    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);
1156
    sendMessage(msg);
lm's avatar
lm committed
1157 1158
}

1159
void UAS::startDataRecording()
lm's avatar
lm committed
1160
{
1161
    mavlink_message_t msg;
1162
    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);
1163
    sendMessage(msg);
lm's avatar
lm committed
1164 1165 1166 1167
}

void UAS::stopDataRecording()
{
1168
    mavlink_message_t msg;
1169
    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);
1170
    sendMessage(msg);
lm's avatar
lm committed
1171 1172
}

pixhawk's avatar
pixhawk committed
1173 1174
void UAS::startMagnetometerCalibration()
{
1175 1176
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1177
    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);
1178
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1179 1180 1181 1182
}

void UAS::startGyroscopeCalibration()
{
1183 1184
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1185
    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);
1186
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1187 1188 1189 1190
}

void UAS::startPressureCalibration()
{
1191 1192
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1193
    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);
1194
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1195 1196
}

LM's avatar
LM committed
1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241
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;
    }
}

1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254
/**
 * @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
1255 1256 1257 1258 1259 1260 1261 1262
/**
 * @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!
 */
1263 1264
quint64 UAS::getUnixTime(quint64 time)
{
1265
    quint64 ret = 0;
LM's avatar
LM committed
1266 1267
    if (attitudeStamped)
    {
1268
        ret = lastAttitude;
LM's avatar
LM committed
1269
    }
1270 1271
    if (time == 0)
    {
1272
        ret = QGC::groundTimeMilliseconds();
1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289
    }
    // 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
1290
#ifndef _MSC_VER
1291
    else if (time < 1261440000000000LLU)
1292
#else
LM's avatar
LM committed
1293
        else if (time < 1261440000000000)
1294
#endif
LM's avatar
LM committed
1295 1296
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1297 1298
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1299
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1300
        }
1301
        ret = time/1000 + onboardTimeOffset;
1302 1303 1304
    }
    else
    {
1305 1306
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1307
        ret = time/1000;
1308
    }
1309
    return ret;
1310 1311
}

1312 1313
QList<QString> UAS::getParameterNames(int component)
{
1314 1315
    if (parameters.contains(component))
    {
1316
        return parameters.value(component)->keys();
1317 1318 1319
    }
    else
    {
1320 1321 1322 1323 1324 1325 1326 1327 1328
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1329
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1330
{
LM's avatar
LM committed
1331 1332 1333 1334 1335
    //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
1336 1337 1338 1339 1340
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1341 1342 1343 1344
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1345
            sendMessage(link, message);
1346 1347 1348
        }
        else
        {
1349 1350 1351
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1352 1353 1354
    }
}

1355 1356 1357 1358
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1359

1360 1361 1362 1363
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1364
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1365 1366 1367 1368 1369 1370
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1371
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1372 1373
                        sendMessage(serial, message);
                    }
1374 1375 1376 1377 1378 1379
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1380 1381
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1382
    if(!link) return;
pixhawk's avatar
pixhawk committed
1383 1384 1385
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1386
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1387 1388
    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
1389
    // If link is connected
1390 1391
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1392 1393 1394 1395 1396 1397 1398 1399
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1400
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1401
{
1402
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1403 1404
}

1405 1406
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1407 1408
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
1409 1410
    switch (mode)
    {
lm's avatar
lm committed
1411
    case 0:
1412
        return QString("PREFLIGHT");
1413 1414 1415 1416
        break;
    default:
        return QString("UNKNOWN");
    }
lm's avatar
lm committed
1417 1418 1419 1420 1421 1422 1423 1424 1425
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1426 1427
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1428 1429
}

pixhawk's avatar
pixhawk committed
1430 1431
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1432 1433
    switch (statusCode)
    {
lm's avatar
lm committed
1434
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1435
        uasState = tr("UNINIT");
1436
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1437
        break;
lm's avatar
lm committed
1438
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1439
        uasState = tr("BOOT");
1440
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1441
        break;
lm's avatar
lm committed
1442
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1443
        uasState = tr("CALIBRATING");
1444
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1445
        break;
lm's avatar
lm committed
1446
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1447
        uasState = tr("ACTIVE");
1448
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1449
        break;
lm's avatar
lm committed
1450 1451
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1452
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1453 1454
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1455
        uasState = tr("CRITICAL");
1456
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1457
        break;
lm's avatar
lm committed
1458
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1459
        uasState = tr("EMERGENCY");
1460
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1461
        break;
James Goppert's avatar
James Goppert committed
1462
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1463 1464 1465
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1466

lm's avatar
lm committed
1467
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1468
        uasState = tr("SHUTDOWN");
1469
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1470
        break;
1471

lm's avatar
lm committed
1472
    default:
pixhawk's avatar
pixhawk committed
1473
        uasState = tr("UNKNOWN");
1474
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1475 1476 1477 1478
        break;
    }
}

1479 1480
QImage UAS::getImage()
{
LM's avatar
LM committed
1481 1482 1483 1484 1485 1486 1487
#ifdef MAVLINK_ENABLED_PIXHAWK

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

    // RAW greyscale
    if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
    {
LM's avatar
LM committed
1488 1489
        // TODO FIXME
        int imgColors = 255;//imageSize/(imageWidth*imageHeight);
LM's avatar
LM committed
1490 1491 1492 1493
        //const int headerSize = 15;

        // Construct PGM header
        QString header("P5\n%1 %2\n%3\n");
LM's avatar
LM committed
1494
        header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
LM's avatar
LM committed
1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524

        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!";
        }
    }
1525 1526
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1527
    //imageRecBuffer.clear();
1528
    return image;
1529 1530
#else
	return QImage();
LM's avatar
LM committed
1531
#endif
1532

1533 1534 1535 1536
}

void UAS::requestImage()
{
1537
#ifdef MAVLINK_ENABLED_PIXHAWK
1538 1539
    qDebug() << "trying to get an image from the uas...";

1540 1541 1542
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1543
        mavlink_message_t msg;
LM's avatar
LM committed
1544
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50);
1545 1546
        sendMessage(msg);
    }
1547
#endif
1548
}
pixhawk's avatar
pixhawk committed
1549 1550 1551 1552 1553 1554 1555 1556 1557


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1558
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1559
{
1560 1561
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1562
        return 0;
1563 1564 1565
    }
    else
    {
pixhawk's avatar
pixhawk committed
1566 1567 1568 1569
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1570
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1571 1572 1573 1574
{
    return commStatus;
}

1575 1576 1577
void UAS::requestParameters()
{
    mavlink_message_t msg;
1578
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1579
    sendMessage(msg);
1580 1581
}

1582
void UAS::writeParametersToStorage()
1583
{
1584
    mavlink_message_t msg;
1585
    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
1586
    qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
1587
    sendMessage(msg);
1588 1589 1590 1591
}

void UAS::readParametersFromStorage()
{
1592
    mavlink_message_t msg;
1593
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
1594
    sendMessage(msg);
lm's avatar
lm committed
1595 1596
}

1597
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1598 1599
{
    // Buffers to write data to
1600
    mavlink_message_t msg;
1601
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1602 1603
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1604
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1605 1606
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1607 1608
    // 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
1609 1610
    stream.req_message_rate = 0;
    // Start / stop the message
1611
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
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
1617
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1618 1619
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1620 1621
}

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

1643
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm 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_EXTENDED_STATUS;
1650
    // Select the update rate in Hz the message should be send
1651
    stream.req_message_rate = rate;
1652
    // Start / stop the message
1653
    stream.start_stop = (rate) ? 1 : 0;
1654 1655 1656 1657 1658 1659
    // 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);
1660 1661
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1662
}
1663

1664
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1665
{
1666 1667 1668 1669 1670
#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
1671 1672 1673
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1674
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1675
    // Select the update rate in Hz the message should be send
1676
    stream.req_message_rate = rate;
1677
    // Start / stop the message
1678
    stream.start_stop = (rate) ? 1 : 0;
1679 1680 1681 1682 1683 1684
    // 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);
1685 1686
    // Send message twice to increase chance of reception
    sendMessage(msg);
1687
#endif
lm's avatar
lm committed
1688 1689
}

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

lm's avatar
lm committed
1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731
//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);
//}
1732

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

1754
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1755 1756 1757 1758 1759
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1760
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1761
    // Select the update rate in Hz the message should be send
1762
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1763
    // Start / stop the message
1764
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775
    // 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);
}

1776
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1777 1778 1779 1780 1781
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1782
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1783
    // Select the update rate in Hz the message should be send
1784
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1785
    // Start / stop the message
1786
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797
    // 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);
}

1798
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1799 1800 1801 1802 1803
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1804
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1805
    // Select the update rate in Hz the message should be send
1806
    stream.req_message_rate = rate;
1807
    // Start / stop the message
1808
    stream.start_stop = (rate) ? 1 : 0;
1809 1810 1811 1812 1813 1814
    // 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);
1815 1816
    // Send message twice to increase chance of reception
    sendMessage(msg);
1817
    sendMessage(msg);
1818 1819
}

lm's avatar
lm committed
1820 1821 1822 1823 1824 1825 1826
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1827
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
lm's avatar
lm committed
1828
{
1829 1830
    if (!id.isNull())
    {
1831 1832
        mavlink_message_t msg;
        mavlink_param_set_t p;
1833 1834 1835 1836 1837 1838 1839
        mavlink_param_union_t union_value;

        // Assign correct value based on QVariant
        switch (value.type())
        {
        case QVariant::Int:
            union_value.param_int32 = value.toInt();
1840
            p.param_type = MAVLINK_TYPE_INT32_T;
1841 1842 1843
            break;
        case QVariant::UInt:
            union_value.param_uint32 = value.toUInt();
1844
            p.param_type = MAVLINK_TYPE_UINT32_T;
1845 1846 1847
            break;
        case QMetaType::Float:
            union_value.param_float = value.toFloat();
1848
            p.param_type = MAVLINK_TYPE_FLOAT;
1849 1850 1851 1852 1853 1854 1855
            break;
        default:
            qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
            return;
        }

        p.param_value = union_value.param_float;
1856 1857 1858
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

1859 1860
        qDebug() << "SENT PARAM:" << value;

1861
        // Copy string into buffer, ensuring not to exceed the buffer size
1862 1863
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1864
            // String characters
1865 1866
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1867 1868
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1869 1870 1871 1872 1873
            //        // 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';
            //        }
1874
            // Zero fill
1875 1876
            else
            {
1877 1878
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1879
        }
1880 1881
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1882
    }
1883 1884
}

1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898
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;
}

1899
void UAS::requestParameter(int component, const QString& parameter)
1900
{
1901
    // Request parameter, use parameter name to request it
1902 1903
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
1904 1905 1906 1907 1908 1909 1910 1911
    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
1912 1913 1914 1915
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
1916
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
1917 1918
}

1919 1920 1921 1922
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
1923 1924 1925 1926
    if (airframe == 0)
    {
        switch (systemType)
        {
lm's avatar
lm committed
1927
        case MAV_TYPE_FIXED_WING:
1928 1929
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
lm's avatar
lm committed
1930
        case MAV_TYPE_QUADROTOR:
1931 1932 1933 1934 1935 1936 1937
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1938 1939
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
1940 1941 1942 1943 1944 1945 1946
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
1947 1948
}

lm's avatar
lm committed
1949 1950 1951
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
1952
    mavlink_command_long_t cmd;
1953 1954 1955 1956 1957 1958
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
1959 1960 1961
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
1962 1963
    cmd.target_system = uasId;
    cmd.target_component = 0;
1964
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1965 1966 1967
    sendMessage(msg);
}

1968 1969 1970 1971
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;
1972 1973 1974 1975 1976 1977
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1978 1979 1980
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
1981 1982
    cmd.target_system = uasId;
    cmd.target_component = component;
1983
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
1984 1985 1986
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1987
/**
lm's avatar
lm committed
1988
 * Launches the system
pixhawk's avatar
pixhawk committed
1989 1990 1991 1992
 *
 **/
void UAS::launch()
{
1993
    mavlink_message_t msg;
1994
    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);
1995
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1996 1997 1998 1999 2000 2001
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
2002
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
2003
{
2004
    mavlink_message_t msg;
2005
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
2006
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2007 2008 2009 2010 2011 2012
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
2013
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
2014
{
2015
    mavlink_message_t msg;
2016
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
2017
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031
}

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
2032 2033
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
2034
    {
2035 2036 2037 2038
        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
2039

2040
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
2041 2042 2043
    }
    else
    {
2044 2045
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2046 2047
}

2048 2049 2050 2051 2052
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2053 2054
void UAS::receiveButton(int buttonIndex)
{
2055 2056
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2057
    case 0:
pixhawk's avatar
pixhawk committed
2058

pixhawk's avatar
pixhawk committed
2059 2060
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2061

pixhawk's avatar
pixhawk committed
2062 2063 2064 2065 2066
        break;
    default:

        break;
    }
2067
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2068 2069 2070

}

2071

pixhawk's avatar
pixhawk committed
2072 2073
void UAS::halt()
{
2074 2075 2076
    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
2077 2078 2079 2080
}

void UAS::go()
{
2081 2082 2083
    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
2084 2085 2086 2087 2088
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
2089 2090 2091 2092 2093 2094 2095 2096 2097
    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
2098 2099 2100 2101 2102 2103 2104 2105
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2106 2107
    // FIXME MAVLINKV10PORTINGNEEDED
    halt();
pixhawk's avatar
pixhawk committed
2108 2109 2110
}

/**
lm's avatar
lm committed
2111
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2112 2113 2114 2115 2116 2117
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
2118
    halt();
lm's avatar
lm committed
2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134 2135 2136 2137 2138 2139 2140 2141 2142 2143 2144
    // 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
2145 2146
}

lm's avatar
lm committed
2147 2148 2149 2150 2151
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2152
        startHil();
lm's avatar
lm committed
2153 2154 2155
    }
    else
    {
2156
        stopHil();
lm's avatar
lm committed
2157 2158 2159 2160 2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183 2184 2185 2186 2187
    }
}

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


2188 2189
void UAS::startHil()
{
lm's avatar
lm committed
2190 2191
    // Connect Flight Gear Link
    simulation->connectSimulation();
2192
    mavlink_message_t msg;
LM's avatar
LM committed
2193
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
2194
    sendMessage(msg);
2195 2196
}

2197 2198
void UAS::stopHil()
{
lm's avatar
lm committed
2199
    simulation->disconnectSimulation();
2200
    mavlink_message_t msg;
LM's avatar
LM committed
2201
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
2202
    sendMessage(msg);
2203 2204 2205
}


pixhawk's avatar
pixhawk committed
2206 2207
void UAS::shutdown()
{
2208 2209 2210 2211 2212
    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
2213

2214 2215 2216
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2217

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

2221 2222 2223 2224
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2225
        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);
2226 2227 2228
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2229 2230
}

2231 2232
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2233
    mavlink_message_t msg;
2234
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 2, 3, 0, yaw, x, y, z);
2235
    sendMessage(msg);
2236 2237
}

pixhawk's avatar
pixhawk committed
2238 2239 2240
/**
 * @return The name of this system as string in human-readable form
 */
2241
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2242 2243
{
    QString result;
2244 2245
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2246
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2247 2248 2249
    }
    else
    {
pixhawk's avatar
pixhawk committed
2250 2251 2252 2253 2254
        result = name;
    }
    return result;
}

2255 2256 2257 2258 2259
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2260 2261 2262
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2263 2264 2265
    uint8_t modeid = id;

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

LM's avatar
LM committed
2267
    // BASE MODE DECODING
pixhawk's avatar
pixhawk committed
2268
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
LM's avatar
LM committed
2269
    {
pixhawk's avatar
pixhawk committed
2270
        mode += "AUTO";
LM's avatar
LM committed
2271
    }
pixhawk's avatar
pixhawk committed
2272
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
LM's avatar
LM committed
2273
    {
pixhawk's avatar
pixhawk committed
2274
        mode += "GUIDED";
LM's avatar
LM committed
2275
    }
pixhawk's avatar
pixhawk committed
2276
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
LM's avatar
LM committed
2277
    {
pixhawk's avatar
pixhawk committed
2278
        mode += "STABILIZED";
LM's avatar
LM committed
2279
    }
pixhawk's avatar
pixhawk committed
2280
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
LM's avatar
LM committed
2281
    {
pixhawk's avatar
pixhawk committed
2282
        mode += "TEST";
LM's avatar
LM committed
2283
    }
pixhawk's avatar
pixhawk committed
2284
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
LM's avatar
LM committed
2285
    {
pixhawk's avatar
pixhawk committed
2286
        mode += "MANUAL";
LM's avatar
LM committed
2287
    }
pixhawk's avatar
pixhawk committed
2288 2289

    if (modeid == 0)
LM's avatar
LM committed
2290
    {
2291
        mode = "PREFLIGHT";
LM's avatar
LM committed
2292 2293 2294
    }

    // ARMED STATE DECODING
pixhawk's avatar
pixhawk committed
2295
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
LM's avatar
LM committed
2296 2297 2298 2299 2300 2301 2302 2303 2304
    {
        mode.prepend("A|");
    }
    else
    {
        mode.prepend("D|");
    }

    // HARDWARE IN THE LOOP DECODING
pixhawk's avatar
pixhawk committed
2305
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
LM's avatar
LM committed
2306 2307
    {
        mode.prepend("HIL:");
2308 2309 2310 2311 2312
    }

    return mode;
}

2313 2314 2315 2316 2317
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2318 2319
void UAS::addLink(LinkInterface* link)
{
2320 2321
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2322
        links->append(link);
2323
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2324 2325 2326
    }
}

2327 2328 2329
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2330 2331
    if (link)
    {
2332 2333 2334 2335
        links->removeAt(links->indexOf(link));
    }
}

LM's avatar
LM committed
2336

pixhawk's avatar
pixhawk committed
2337 2338 2339 2340 2341
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}

LM's avatar
LM committed
2342 2343 2344 2345 2346
QMap<int, QString> UAS::getComponents()
{
    return components;
}

pixhawk's avatar
pixhawk committed
2347 2348 2349 2350 2351 2352


void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2353 2354
    switch (batteryType)
    {
lm's avatar
lm committed
2355
    case NICD:
pixhawk's avatar
pixhawk committed
2356
        break;
lm's avatar
lm committed
2357
    case NIMH:
pixhawk's avatar
pixhawk committed
2358
        break;
lm's avatar
lm committed
2359
    case LIION:
pixhawk's avatar
pixhawk committed
2360
        break;
lm's avatar
lm committed
2361
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2362 2363 2364
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2365
    case LIFE:
pixhawk's avatar
pixhawk committed
2366
        break;
lm's avatar
lm committed
2367
    case AGZN:
pixhawk's avatar
pixhawk committed
2368 2369 2370 2371
        break;
    }
}

2372 2373
void UAS::setBatterySpecs(const QString& specs)
{
2374 2375
    if (specs.length() == 0 || specs.contains("%"))
    {
2376
        batteryRemainingEstimateEnabled = false;
2377
        bool ok;
2378 2379 2380
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2381 2382
        if (ok)
        {
2383
            warnLevelPercent = temp;
2384 2385 2386
        }
        else
        {
2387 2388
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2389 2390 2391
    }
    else
    {
2392 2393 2394 2395 2396
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2397 2398
        if (parts.length() == 3)
        {
2399 2400 2401 2402 2403 2404 2405 2406 2407 2408 2409
            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;
2410 2411 2412
        }
        else
        {
2413 2414
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2415 2416 2417 2418 2419
    }
}

QString UAS::getBatterySpecs()
{
2420 2421
    if (batteryRemainingEstimateEnabled)
    {
2422
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2423 2424 2425
    }
    else
    {
2426 2427
        return QString("%1%").arg(warnLevelPercent);
    }
2428 2429
}

pixhawk's avatar
pixhawk committed
2430 2431 2432 2433 2434 2435 2436 2437 2438 2439 2440 2441 2442
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
2443 2444 2445
/**
 * @return charge level in percent - 0 - 100
 */
2446
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2447
{
2448 2449 2450 2451
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2452
            chargeLevel = 0.0f;
2453 2454 2455
        }
        else if (lpVoltage > fullVoltage)
        {
2456
            chargeLevel = 100.0f;
2457 2458 2459
        }
        else
        {
2460 2461
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2462 2463
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2464 2465
}

lm's avatar
lm committed
2466 2467
void UAS::startLowBattAlarm()
{
2468 2469
    if (!lowBattAlarm)
    {
2470
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2471
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2472 2473 2474 2475 2476 2477
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2478 2479
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2480 2481 2482 2483
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}