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

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

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

30
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lm's avatar
lm committed
31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83
    uasId(id),
    startTime(QGC::groundTimeMilliseconds()),
    commStatus(COMM_DISCONNECTED),
    name(""),
    autopilot(-1),
    links(new QList<LinkInterface*>()),
    unknownPackets(),
    mavlink(protocol),
    waypointManager(this),
    thrustSum(0),
    thrustMax(10),
    startVoltage(0),
    warnVoltage(9.5f),
    warnLevelPercent(20.0f),
    currentVoltage(12.0f),
    lpVoltage(12.0f),
    batteryRemainingEstimateEnabled(true),
    mode(-1),
    status(-1),
    navMode(-1),
    onboardTimeOffset(0),
    controlRollManual(true),
    controlPitchManual(true),
    controlYawManual(true),
    controlThrustManual(true),
    manualRollAngle(0),
    manualPitchAngle(0),
    manualYawAngle(0),
    manualThrust(0),
    receiveDropRate(0),
    sendDropRate(0),
    lowBattAlarm(false),
    positionLock(false),
    localX(0.0),
    localY(0.0),
    localZ(0.0),
    latitude(0.0),
    longitude(0.0),
    altitude(0.0),
    roll(0.0),
    pitch(0.0),
    yaw(0.0),
    statusTimeout(new QTimer(this)),
    paramsOnceRequested(false),
    airframe(QGC_AIRFRAME_EASYSTAR),
    attitudeKnown(false),
    paramManager(NULL),
    attitudeStamped(false),
    lastAttitude(0),
    simulation(new QGCFlightGearLink(this)),
    isLocalPositionKnown(false),
    isGlobalPositionKnown(false),
    systemIsArmed(false)
pixhawk's avatar
pixhawk committed
84
{
85
    color = UASInterface::getNextColor();
lm's avatar
lm committed
86
    setBatterySpecs(QString("9V,9.5V,12.6V"));
87
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
88
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
89
    statusTimeout->start(500);
90
    readSettings();
91 92 93 94

    // Initial signals
    emit disarmed();
    emit armingChanged(false);
pixhawk's avatar
pixhawk committed
95 96 97 98
}

UAS::~UAS()
{
99
    writeSettings();
pixhawk's avatar
pixhawk committed
100
    delete links;
101
    links=NULL;
pixhawk's avatar
pixhawk committed
102 103
}

104 105 106 107 108
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
109 110
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
111
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
112 113 114 115 116 117 118 119 120
    settings.endGroup();
    settings.sync();
}

void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
121 122
    this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
    this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
123
    if (settings.contains("BATTERY_SPECS")) {
124 125
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
126 127 128
    settings.endGroup();
}

129
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
130 131 132 133
{
    return uasId;
}

134 135
void UAS::updateState()
{
136 137
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
138 139
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
140 141 142 143
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

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

pixhawk's avatar
pixhawk committed
159 160
void UAS::setSelected()
{
161
    if (UASManager::instance()->getActiveUAS() != this) {
162 163 164 165 166 167 168 169
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

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

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

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

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

LM's avatar
LM committed
205 206 207 208
    // 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))
209
    {
pixhawk's avatar
pixhawk committed
210 211
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
212

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

244 245 246 247 248 249 250 251 252 253 254 255 256 257 258
            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();
                }
            }
259

260 261 262 263 264 265
            QString audiostring = "System " + getUASName();
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
266 267


268 269 270 271 272 273 274
            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);
275

276
                shortStateText = uasState;
277

278 279
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
280

281
            if (this->mode != static_cast<int>(state.base_mode))
282 283
            {
                modechanged = true;
284
                this->mode = static_cast<int>(state.base_mode);
285
                shortModeText = getShortModeTextFor(this->mode);
286

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

289 290
                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed
291

292
            if (navMode != state.custom_mode)
293
            {
294 295
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
296 297
                navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
            }
298

299 300 301 302 303 304 305 306 307 308 309
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
310

311 312 313 314 315 316 317
            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();
318
                GAudioOutput::instance()->say(audiostring.toLower());
319
            }
lm's avatar
lm committed
320

321 322 323 324 325
//            if (state.system_status == MAV_STATE_POWEROFF)
//            {
//                emit systemRemoved(this);
//                emit systemRemoved();
//            }
326
}
327

328 329 330 331 332 333 334 335 336 337
            break;
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
            // Receive named value message
            receiveMessageNamedValue(message);
            break;
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
338

339
                emit loadChanged(this,state.load/10.0f);
LM's avatar
LM committed
340 341


342

343
                currentVoltage = state.voltage_battery/1000.0f;
LM's avatar
LM committed
344
                lpVoltage = filterVoltage(currentVoltage);
LM's avatar
LM committed
345 346 347

                qDebug() << "BATT VOLTAGE:" << currentVoltage << "RAW" << state.voltage_battery;

LM's avatar
LM committed
348 349
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
350
                if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
351
                {
352
                    chargeLevel = state.battery_remaining;
LM's avatar
LM committed
353 354 355
                }
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
356
                emit voltageChanged(message.sysid, state.voltage_battery/1000);
357

LM's avatar
LM committed
358
                // LOW BATTERY ALARM
359 360
                if (lpVoltage < warnVoltage)
                {
LM's avatar
LM committed
361
                    startLowBattAlarm();
362 363 364
                }
                else
                {
LM's avatar
LM committed
365 366
                    stopLowBattAlarm();
                }
367

LM's avatar
LM committed
368
                // COMMUNICATIONS DROP RATE
369 370
                // FIXME
                emit dropRateChanged(this->getUASID(), state.drop_rate_comm/10000.0f);
371
            }
LM's avatar
LM committed
372
            break;
pixhawk's avatar
pixhawk committed
373
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
374 375 376
            {
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
377
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
LM's avatar
LM committed
378
                lastAttitude = time;
LM's avatar
LM committed
379 380 381 382 383 384 385 386 387
                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);

                // Emit in angles

                // Convert yaw angle to compass value
                // in 0 - 360 deg range
                float compass = (yaw/M_PI)*180.0+360.0f;
lm's avatar
lm committed
388 389 390 391 392
                if (compass > -10000 && compass < 10000)
                {
                    while (compass > 360.0f) {
                        compass -= 360.0f;
                    }
LM's avatar
LM committed
393
                }
lm's avatar
lm committed
394

LM's avatar
LM committed
395
                attitudeKnown = true;
396
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
397
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
398
            }
LM's avatar
LM committed
399
            break;
lm's avatar
lm committed
400 401 402 403
        case MAVLINK_MSG_ID_HIL_CONTROLS:
            {
                mavlink_hil_controls_t hil;
                mavlink_msg_hil_controls_decode(&message, &hil);
404
                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
405 406
            }
            break;
407 408
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
409 410 411 412 413 414
                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);

415 416
                if (!attitudeKnown)
                {
LM's avatar
LM committed
417 418 419
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
420

LM's avatar
LM committed
421
                emit altitudeChanged(uasId, hud.alt);
LM's avatar
LM committed
422
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
LM's avatar
LM committed
423 424
            }
            break;
lm's avatar
lm committed
425
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
lm's avatar
lm committed
426
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
427
            //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
428
            {
lm's avatar
lm committed
429 430
                mavlink_local_position_ned_t pos;
                mavlink_msg_local_position_ned_decode(&message, &pos);
431
                quint64 time = getUnixTime(pos.time_boot_ms);
LM's avatar
LM committed
432 433 434 435 436 437 438 439 440 441 442 443
                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;
444
                isLocalPositionKnown = true;
lm's avatar
lm committed
445
            }
LM's avatar
LM committed
446
            break;
447
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
448 449
            //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
450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467
            {
                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
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
468
                isGlobalPositionKnown = true;
LM's avatar
LM committed
469 470
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
471
            }
LM's avatar
LM committed
472
            break;
473 474
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
LM's avatar
LM committed
475 476 477 478 479
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);

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

LM's avatar
LM committed
483
                if (pos.fix_type > 2) {
LM's avatar
LM committed
484 485 486 487 488 489 490 491 492 493 494 495
                    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;

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt) {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
lm's avatar
lm committed
496
                    // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
LM's avatar
LM committed
497
                    // Smaller than threshold and not NaN
LM's avatar
LM committed
498 499 500 501

                    float vel = pos.vel/100.0f;

                    if (vel < 1000000 && !isnan(vel) && !isinf(vel)) {
lm's avatar
lm committed
502
                        // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time);
LM's avatar
LM committed
503 504 505
                        //qDebug() << "GOT GPS RAW";
                        // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    } else {
LM's avatar
LM committed
506
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
LM's avatar
LM committed
507
                    }
lm's avatar
lm committed
508 509
                }
            }
LM's avatar
LM committed
510
            break;
511 512
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
LM's avatar
LM committed
513 514
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
515 516
                for(int i = 0; i < (int)pos.satellites_visible; i++)
                {
LM's avatar
LM committed
517 518
                    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]));
                }
519
            }
LM's avatar
LM committed
520
            break;
521
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
522
            {
523 524
                mavlink_gps_global_origin_t pos;
                mavlink_msg_gps_global_origin_decode(&message, &pos);
LM's avatar
LM committed
525
                emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
LM's avatar
LM committed
526 527
            }
            break;
528 529
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            {
LM's avatar
LM committed
530 531 532 533 534 535 536 537 538 539 540 541 542
                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;
543 544
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
LM's avatar
LM committed
545 546 547 548 549 550 551 552 553 554 555
                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
556
            }
LM's avatar
LM committed
557
            break;
558 559
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
LM's avatar
LM committed
560 561
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
562
                QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
LM's avatar
LM committed
563 564
                QString parameterName = QString(bytes);
                int component = message.compid;
565 566
                mavlink_param_union_t val;
                val.param_float = value.param_value;
567
                val.type = value.param_type;
568

LM's avatar
LM committed
569
                // Insert component if necessary
570 571
                if (!parameters.contains(component))
                {
572
                    parameters.insert(component, new QMap<QString, QVariant>());
LM's avatar
LM committed
573
                }
574

LM's avatar
LM committed
575 576
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
577

578 579 580
                // Insert with correct type
                switch (value.param_type)
                {
581
                case MAVLINK_TYPE_FLOAT:
582 583 584 585
                    {
                    // Variant
                    QVariant param(val.param_float);
                    parameters.value(component)->insert(parameterName, param);
586
                    // Emit change
587 588 589 590
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
591
                    break;
592
                case MAVLINK_TYPE_UINT32_T:
593 594 595 596
                    {
                    // Variant
                    QVariant param(val.param_uint32);
                    parameters.value(component)->insert(parameterName, param);
597
                    // Emit change
598 599 600 601
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
602
                    break;
603
                case MAVLINK_TYPE_INT32_T:
604 605 606 607
                    {
                    // Variant
                    QVariant param(val.param_int32);
                    parameters.value(component)->insert(parameterName, param);
608
                    // Emit change
609 610 611 612
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
613 614 615 616
                    break;
                default:
                    qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
                }
LM's avatar
LM committed
617 618
            }
            break;
619 620 621
        case MAVLINK_MSG_ID_COMMAND_ACK:
            mavlink_command_ack_t ack;
            mavlink_msg_command_ack_decode(&message, &ack);
622 623
            if (ack.result == 1)
            {
624
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
625 626 627
            }
            else
            {
628
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
629 630
            }
            break;
LM's avatar
LM committed
631
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
632
            {
LM's avatar
LM committed
633 634
                mavlink_roll_pitch_yaw_thrust_setpoint_t out;
                mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
635
                quint64 time = getUnixTimeFromMs(out.time_boot_ms);
LM's avatar
LM committed
636
                emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
LM's avatar
LM committed
637 638
            }
            break;
lm's avatar
lm committed
639
        case MAVLINK_MSG_ID_MISSION_COUNT:
640
            {
lm's avatar
lm committed
641 642
                mavlink_mission_count_t wpc;
                mavlink_msg_mission_count_decode(&message, &wpc);
643
                if (wpc.target_system == mavlink->getSystemId())
644
                {
LM's avatar
LM committed
645 646
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
LM's avatar
LM committed
647 648 649 650
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
651
            }
LM's avatar
LM committed
652
            break;
pixhawk's avatar
pixhawk committed
653

lm's avatar
lm committed
654
        case MAVLINK_MSG_ID_MISSION_ITEM:
655
            {
lm's avatar
lm committed
656 657
                mavlink_mission_item_t wp;
                mavlink_msg_mission_item_decode(&message, &wp);
LM's avatar
LM committed
658
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
659
                if(wp.target_system == mavlink->getSystemId())
660
                {
LM's avatar
LM committed
661 662
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
LM's avatar
LM committed
663 664 665 666
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
667
            }
LM's avatar
LM committed
668
            break;
pixhawk's avatar
pixhawk committed
669

lm's avatar
lm committed
670
        case MAVLINK_MSG_ID_MISSION_ACK:
671
            {
lm's avatar
lm committed
672 673
                mavlink_mission_ack_t wpa;
                mavlink_msg_mission_ack_decode(&message, &wpa);
674 675
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
676 677
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
678
            }
LM's avatar
LM committed
679
            break;
680

lm's avatar
lm committed
681
        case MAVLINK_MSG_ID_MISSION_REQUEST:
682
            {
lm's avatar
lm committed
683 684
                mavlink_mission_request_t wpr;
                mavlink_msg_mission_request_decode(&message, &wpr);
685
                if(wpr.target_system == mavlink->getSystemId())
686
                {
LM's avatar
LM committed
687 688
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
LM's avatar
LM committed
689 690 691 692
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
693
            }
LM's avatar
LM committed
694
            break;
pixhawk's avatar
pixhawk committed
695

lm's avatar
lm committed
696
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
697
            {
lm's avatar
lm committed
698 699
                mavlink_mission_item_reached_t wpr;
                mavlink_msg_mission_item_reached_decode(&message, &wpr);
LM's avatar
LM committed
700 701 702 703 704 705
                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
706

lm's avatar
lm committed
707
        case MAVLINK_MSG_ID_MISSION_CURRENT:
708
            {
lm's avatar
lm committed
709 710
                mavlink_mission_current_t wpc;
                mavlink_msg_mission_current_decode(&message, &wpc);
LM's avatar
LM committed
711 712 713
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
714

715 716
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
717 718 719 720 721
                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;
722 723
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
724 725
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
lm's avatar
lm committed
726
                mavlink_msg_statustext_get_text(&message, b.data());
LM's avatar
LM committed
727 728 729 730 731 732 733 734
                //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;
735
#ifdef MAVLINK_ENABLED_PIXHAWK
736 737
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
738 739 740 741 742 743 744 745 746 747 748
                qDebug() << "RECIEVED ACK TO GET IMAGE";
                mavlink_data_transmission_handshake_t p;
                mavlink_msg_data_transmission_handshake_decode(&message, &p);
                imageSize = p.size;
                imagePackets = p.packets;
                imagePayload = p.payload;
                imageQuality = p.jpg_quality;
                imageType = p.type;
                imageStart = QGC::groundTimeMilliseconds();
            }
            break;
749

750 751
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
752 753 754 755 756 757 758 759 760 761 762
                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;
763 764
                }

765 766
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
767 768 769 770 771
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
772

LM's avatar
LM committed
773
                ++imagePacketsArrived;
774

LM's avatar
LM committed
775 776 777 778 779 780 781 782
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    imagePacketsArrived = 0;
                    emit imageReady(this);
                    qDebug() << "imageReady emitted. all packets arrived";
                }
783
            }
LM's avatar
LM committed
784
            break;
785
#endif
lm's avatar
lm committed
786 787 788 789 790 791 792 793
//        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;
794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812
        // 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
813
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
814 815 816
//                    break;
//                case 1:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
817
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
818 819 820
//                    break;
//                case 2:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
821
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
822 823 824
//                    break;
//                case 3:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
825
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
826 827 828
//                    break;
//                case 4:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
829
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
830 831 832
//                    break;
//                case 5:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
833
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
834 835 836
//                    break;
//                case 6:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
837
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
838 839 840 841 842
//                    break;
//                }
//            }
//        }
//        break;
lm's avatar
lm committed
843
#ifdef MAVLINK_ENABLED_UALBERTA
844 845
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
LM's avatar
LM committed
846 847 848
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = getUnixTime();
lm's avatar
lm committed
849 850 851 852 853 854
                // 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
855 856
            }
            break;
857 858
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
LM's avatar
LM committed
859 860
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
861 862 863 864 865 866
                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
867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885

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

887
#endif
LM's avatar
LM committed
888
            // Messages to ignore
889
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
lm's avatar
lm committed
890 891 892 893 894 895 896
        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:
897
            break;
lm's avatar
lm committed
898
        case MAVLINK_MSG_ID_DEBUG_VECT:
LM's avatar
LM committed
899 900 901
            {
                mavlink_debug_vect_t debug;
                mavlink_msg_debug_vect_decode(&message, &debug);
902
                debug.name[MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN-1] = '\0';
LM's avatar
LM committed
903 904 905 906 907 908 909
                QString name(debug.name);
                quint64 time = getUnixTime(debug.time_usec);
                emit valueChanged(uasId, name+".x", "raw", debug.x, time);
                emit valueChanged(uasId, name+".y", "raw", debug.y, time);
                emit valueChanged(uasId, name+".z", "raw", debug.z, time);
            }
            break;
LM's avatar
LM committed
910
        case MAVLINK_MSG_ID_DEBUG:
911
            break;
912 913 914 915
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
916 917 918 919 920 921 922
                    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
923
            }
LM's avatar
LM committed
924
            break;
pixhawk's avatar
pixhawk committed
925 926 927 928
        }
    }
}

929 930
void UAS::setHomePosition(double lat, double lon, double alt)
{
931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963
    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);
    }
964 965
}

966 967 968 969 970 971 972 973 974 975 976 977 978 979
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()));


980 981
    if (ret == QMessageBox::Yes)
    {
982 983 984 985 986 987 988 989
        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);
990 991 992
    }
}

pixhawk's avatar
pixhawk committed
993 994
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
995
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
996
    mavlink_message_t msg;
LM's avatar
LM committed
997
    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
998
    sendMessage(msg);
999
#else
lm's avatar
lm committed
1000 1001 1002 1003
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1004
#endif
pixhawk's avatar
pixhawk committed
1005 1006
}

pixhawk's avatar
pixhawk committed
1007 1008
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1009
#ifdef MAVLINK_ENABLED_PIXHAWK
1010 1011 1012
    mavlink_message_t msg;
    mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
    sendMessage(msg);
lm's avatar
lm committed
1013
#else
1014 1015 1016 1017
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1018 1019 1020 1021
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1022
{
1023 1024
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1025
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1);
1026
    sendMessage(msg);
lm's avatar
lm committed
1027 1028
}

1029
void UAS::startDataRecording()
lm's avatar
lm committed
1030
{
1031
    mavlink_message_t msg;
1032
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2);
1033
    sendMessage(msg);
lm's avatar
lm committed
1034 1035 1036 1037
}

void UAS::stopDataRecording()
{
1038
    mavlink_message_t msg;
1039
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0);
1040
    sendMessage(msg);
lm's avatar
lm committed
1041 1042
}

pixhawk's avatar
pixhawk committed
1043 1044
void UAS::startMagnetometerCalibration()
{
1045 1046
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1047
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0);
1048
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1049 1050 1051 1052
}

void UAS::startGyroscopeCalibration()
{
1053 1054
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1055
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0);
1056
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1057 1058 1059 1060
}

void UAS::startPressureCalibration()
{
1061 1062
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1063
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0);
1064
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1065 1066
}

LM's avatar
LM committed
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 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111
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;
    }
}

1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124
/**
 * @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
1125 1126 1127 1128 1129 1130 1131 1132
/**
 * @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!
 */
1133 1134
quint64 UAS::getUnixTime(quint64 time)
{
1135
    quint64 ret = 0;
LM's avatar
LM committed
1136 1137
    if (attitudeStamped)
    {
1138
        ret = lastAttitude;
LM's avatar
LM committed
1139
    }
1140 1141
    if (time == 0)
    {
1142
        ret = QGC::groundTimeMilliseconds();
1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159
    }
    // 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
1160
#ifndef _MSC_VER
1161
    else if (time < 1261440000000000LLU)
1162
#else
LM's avatar
LM committed
1163
        else if (time < 1261440000000000)
1164
#endif
LM's avatar
LM committed
1165 1166
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1167 1168
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1169
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1170
        }
1171
        ret = time/1000 + onboardTimeOffset;
1172 1173 1174
    }
    else
    {
1175 1176
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1177
        ret = time/1000;
1178
    }
1179
    return ret;
1180 1181
}

1182 1183
QList<QString> UAS::getParameterNames(int component)
{
1184 1185
    if (parameters.contains(component))
    {
1186
        return parameters.value(component)->keys();
1187 1188 1189
    }
    else
    {
1190 1191 1192 1193 1194 1195 1196 1197 1198
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1199
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1200
{
LM's avatar
LM committed
1201 1202 1203 1204 1205
    //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
1206 1207 1208 1209 1210
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1211 1212 1213 1214
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1215
            sendMessage(link, message);
1216 1217 1218
        }
        else
        {
1219 1220 1221
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1222 1223 1224
    }
}

1225 1226 1227 1228
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1229

1230 1231 1232 1233
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1234
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1235 1236 1237 1238 1239 1240
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1241
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1242 1243
                        sendMessage(serial, message);
                    }
1244 1245 1246 1247 1248 1249
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1250 1251
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1252
    if(!link) return;
pixhawk's avatar
pixhawk committed
1253 1254 1255
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1256
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1257 1258
    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
1259
    // If link is connected
1260 1261
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1262 1263 1264 1265 1266 1267 1268 1269
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1270
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1271
{
1272
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1273 1274
}

1275 1276
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1277 1278
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
1279 1280
    switch (mode)
    {
lm's avatar
lm committed
1281
    case 0:
1282
        return QString("PREFLIGHT");
1283 1284 1285 1286
        break;
    default:
        return QString("UNKNOWN");
    }
lm's avatar
lm committed
1287 1288 1289 1290 1291 1292 1293 1294 1295
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1296 1297
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1298 1299
}

pixhawk's avatar
pixhawk committed
1300 1301
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1302 1303
    switch (statusCode)
    {
lm's avatar
lm committed
1304
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1305
        uasState = tr("UNINIT");
1306
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1307
        break;
lm's avatar
lm committed
1308
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1309
        uasState = tr("BOOT");
1310
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1311
        break;
lm's avatar
lm committed
1312
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1313
        uasState = tr("CALIBRATING");
1314
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1315
        break;
lm's avatar
lm committed
1316
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1317
        uasState = tr("ACTIVE");
1318
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1319
        break;
lm's avatar
lm committed
1320 1321
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1322
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1323 1324
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1325
        uasState = tr("CRITICAL");
1326
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1327
        break;
lm's avatar
lm committed
1328
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1329
        uasState = tr("EMERGENCY");
1330
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1331
        break;
James Goppert's avatar
James Goppert committed
1332
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1333 1334 1335
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1336

lm's avatar
lm committed
1337
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1338
        uasState = tr("SHUTDOWN");
1339
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1340
        break;
1341

lm's avatar
lm committed
1342
    default:
pixhawk's avatar
pixhawk committed
1343
        uasState = tr("UNKNOWN");
1344
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1345 1346 1347 1348
        break;
    }
}

1349 1350
QImage UAS::getImage()
{
LM's avatar
LM committed
1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397
#ifdef MAVLINK_ENABLED_PIXHAWK

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

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

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

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

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

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

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

    }
    // BMP with header
    else if (imageType == MAVLINK_DATA_STREAM_IMG_BMP ||
             imageType == MAVLINK_DATA_STREAM_IMG_JPEG ||
             imageType == MAVLINK_DATA_STREAM_IMG_PGM ||
             imageType == MAVLINK_DATA_STREAM_IMG_PNG)
    {
       if (!image.loadFromData(imageRecBuffer))
        {
           qDebug() << "Loading data from image buffer failed!";
        }
    }
1398 1399
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1400
    //imageRecBuffer.clear();
1401
    return image;
1402 1403
#else
	return QImage();
LM's avatar
LM committed
1404
#endif
1405

1406 1407 1408 1409
}

void UAS::requestImage()
{
1410
#ifdef MAVLINK_ENABLED_PIXHAWK
1411 1412
    qDebug() << "trying to get an image from the uas...";

1413 1414 1415
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1416 1417 1418 1419
        mavlink_message_t msg;
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 50);
        sendMessage(msg);
    }
1420
#endif
1421
}
pixhawk's avatar
pixhawk committed
1422 1423 1424 1425 1426 1427 1428 1429 1430


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1431
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1432
{
1433 1434
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1435
        return 0;
1436 1437 1438
    }
    else
    {
pixhawk's avatar
pixhawk committed
1439 1440 1441 1442
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1443
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1444 1445 1446 1447
{
    return commStatus;
}

1448 1449 1450
void UAS::requestParameters()
{
    mavlink_message_t msg;
1451
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1452
    sendMessage(msg);
1453 1454
}

1455
void UAS::writeParametersToStorage()
1456
{
1457
    mavlink_message_t msg;
1458
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1);
1459
    sendMessage(msg);
1460 1461 1462 1463
}

void UAS::readParametersFromStorage()
{
1464
    mavlink_message_t msg;
1465
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1);
1466
    sendMessage(msg);
lm's avatar
lm committed
1467 1468
}

1469
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1470 1471
{
    // Buffers to write data to
1472
    mavlink_message_t msg;
1473
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1474 1475
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1476
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1477 1478
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1479 1480
    // 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
1481 1482
    stream.req_message_rate = 0;
    // Start / stop the message
1483
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1484 1485 1486 1487 1488
    // 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
1489
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1490 1491
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1492 1493 1494
    sendMessage(msg);
}

1495
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1496 1497 1498
{
    // Buffers to write data to
    mavlink_message_t msg;
1499
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1500
    // Select the message to request from now on
1501
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1502
    // Select the update rate in Hz the message should be send
1503
    stream.req_message_rate = rate;
lm's avatar
lm committed
1504
    // Start / stop the message
1505
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1506 1507 1508 1509 1510
    // 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
1511
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1512 1513
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1514 1515 1516
    sendMessage(msg);
}

1517
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1518
{
1519 1520 1521 1522
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1523
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1524
    // Select the update rate in Hz the message should be send
1525
    stream.req_message_rate = rate;
1526
    // Start / stop the message
1527
    stream.start_stop = (rate) ? 1 : 0;
1528 1529 1530 1531 1532 1533
    // 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);
1534 1535
    // Send message twice to increase chance of reception
    sendMessage(msg);
1536
    sendMessage(msg);
lm's avatar
lm committed
1537
}
1538

1539
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1540
{
1541 1542 1543 1544 1545
#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
1546 1547 1548
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1549
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1550
    // Select the update rate in Hz the message should be send
1551
    stream.req_message_rate = rate;
1552
    // Start / stop the message
1553
    stream.start_stop = (rate) ? 1 : 0;
1554 1555 1556 1557 1558 1559
    // 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);
1560 1561
    // Send message twice to increase chance of reception
    sendMessage(msg);
1562
    sendMessage(msg);
1563
#endif
lm's avatar
lm committed
1564 1565
}

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

lm's avatar
lm committed
1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608
//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);
//}
1609

1610
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1611 1612 1613 1614 1615
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1616
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1617
    // Select the update rate in Hz the message should be send
1618
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1619
    // Start / stop the message
1620
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631
    // 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);
}

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

1654
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1655 1656 1657 1658 1659
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1660
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1661
    // Select the update rate in Hz the message should be send
1662
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1663
    // Start / stop the message
1664
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675
    // 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);
}

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

lm's avatar
lm committed
1698 1699 1700 1701 1702 1703 1704
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1705
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
lm's avatar
lm committed
1706
{
1707 1708
    if (!id.isNull())
    {
1709 1710
        mavlink_message_t msg;
        mavlink_param_set_t p;
1711 1712 1713 1714 1715 1716 1717
        mavlink_param_union_t union_value;

        // Assign correct value based on QVariant
        switch (value.type())
        {
        case QVariant::Int:
            union_value.param_int32 = value.toInt();
1718
            p.param_type = MAVLINK_TYPE_INT32_T;
1719 1720 1721
            break;
        case QVariant::UInt:
            union_value.param_uint32 = value.toUInt();
1722
            p.param_type = MAVLINK_TYPE_UINT32_T;
1723 1724 1725
            break;
        case QMetaType::Float:
            union_value.param_float = value.toFloat();
1726
            p.param_type = MAVLINK_TYPE_FLOAT;
1727 1728 1729 1730 1731 1732 1733
            break;
        default:
            qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
            return;
        }

        p.param_value = union_value.param_float;
1734 1735 1736
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

1737 1738
        qDebug() << "SENT PARAM:" << value;

1739
        // Copy string into buffer, ensuring not to exceed the buffer size
1740 1741
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1742
            // String characters
1743 1744
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1745 1746
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1747 1748 1749 1750 1751
            //        // 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';
            //        }
1752
            // Zero fill
1753 1754
            else
            {
1755 1756
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1757
        }
1758 1759
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1760
    }
1761 1762
}

1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776
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;
}

1777
void UAS::requestParameter(int component, const QString& parameter)
1778
{
1779
    // Request parameter, use parameter name to request it
1780 1781
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
1782 1783 1784 1785 1786 1787 1788 1789
    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
1790 1791 1792 1793
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
1794
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
1795 1796
}

1797 1798 1799 1800
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
1801 1802 1803 1804
    if (airframe == 0)
    {
        switch (systemType)
        {
lm's avatar
lm committed
1805
        case MAV_TYPE_FIXED_WING:
1806 1807
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
lm's avatar
lm committed
1808
        case MAV_TYPE_QUADROTOR:
1809 1810 1811 1812 1813 1814 1815
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1816 1817
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
1818 1819 1820 1821 1822 1823 1824
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
1825 1826
}

lm's avatar
lm committed
1827 1828 1829
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
1830
    mavlink_command_short_t cmd;
1831 1832 1833 1834 1835 1836 1837 1838
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
    cmd.target_system = uasId;
    cmd.target_component = 0;
1839
    mavlink_msg_command_short_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1840 1841 1842 1843 1844 1845
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
1846
    mavlink_command_short_t cmd;
1847 1848 1849 1850 1851 1852 1853 1854
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
    cmd.target_system = uasId;
    cmd.target_component = component;
1855 1856 1857 1858 1859 1860 1861 1862
    mavlink_msg_command_short_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
    sendMessage(msg);
}

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

pixhawk's avatar
pixhawk committed
1878
/**
lm's avatar
lm committed
1879
 * Launches the system
pixhawk's avatar
pixhawk committed
1880 1881 1882 1883
 *
 **/
void UAS::launch()
{
1884 1885 1886
    mavlink_message_t msg;
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_NAV_TAKEOFF, 1, 0, 0, 0, 0);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1887 1888 1889 1890 1891 1892
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
1893
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
1894
{
1895
    mavlink_message_t msg;
1896
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
1897
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1898 1899 1900 1901 1902 1903
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
1904
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
1905
{
1906
    mavlink_message_t msg;
1907
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
1908
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921 1922
}

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
1923 1924
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
1925
    {
1926 1927 1928 1929
        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
1930

1931
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
1932 1933 1934
    }
    else
    {
1935 1936
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
1937 1938
}

1939 1940 1941 1942 1943
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1944 1945
void UAS::receiveButton(int buttonIndex)
{
1946 1947
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
1948
    case 0:
pixhawk's avatar
pixhawk committed
1949

pixhawk's avatar
pixhawk committed
1950 1951
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1952

pixhawk's avatar
pixhawk committed
1953 1954 1955 1956 1957
        break;
    default:

        break;
    }
1958
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1959 1960 1961

}

1962

pixhawk's avatar
pixhawk committed
1963 1964
void UAS::halt()
{
1965 1966 1967
    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
1968 1969 1970 1971
}

void UAS::go()
{
1972 1973 1974
    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
1975 1976 1977 1978 1979
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1980 1981 1982 1983 1984 1985 1986 1987 1988
    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
1989 1990 1991 1992 1993 1994 1995 1996
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1997 1998
    // FIXME MAVLINKV10PORTINGNEEDED
    halt();
pixhawk's avatar
pixhawk committed
1999 2000 2001
}

/**
lm's avatar
lm committed
2002
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2003 2004 2005 2006 2007 2008
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
2009
    halt();
lm's avatar
lm committed
2010 2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035
    // 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
2036 2037
}

lm's avatar
lm committed
2038 2039 2040 2041 2042
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2043
        startHil();
lm's avatar
lm committed
2044 2045 2046
    }
    else
    {
2047
        stopHil();
lm's avatar
lm committed
2048 2049 2050 2051 2052 2053 2054 2055 2056 2057 2058 2059 2060 2061 2062 2063 2064 2065 2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077 2078
    }
}

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


2079 2080
void UAS::startHil()
{
lm's avatar
lm committed
2081 2082
    // Connect Flight Gear Link
    simulation->connectSimulation();
2083
    mavlink_message_t msg;
LM's avatar
LM committed
2084
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
2085
    sendMessage(msg);
2086 2087
}

2088 2089
void UAS::stopHil()
{
lm's avatar
lm committed
2090
    simulation->disconnectSimulation();
2091
    mavlink_message_t msg;
LM's avatar
LM committed
2092
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
2093
    sendMessage(msg);
2094 2095 2096
}


pixhawk's avatar
pixhawk committed
2097 2098
void UAS::shutdown()
{
2099 2100 2101 2102 2103
    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
2104

2105 2106 2107
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2108

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

2112 2113 2114 2115 2116 2117 2118 2119
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
        mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 0, 2, 0, 0, 0);
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2120 2121
}

2122 2123
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2124
    mavlink_message_t msg;
lm's avatar
lm committed
2125
    mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw);
2126
    sendMessage(msg);
2127 2128
}

pixhawk's avatar
pixhawk committed
2129 2130 2131
/**
 * @return The name of this system as string in human-readable form
 */
2132
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2133 2134
{
    QString result;
2135 2136
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2137
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2138 2139 2140
    }
    else
    {
pixhawk's avatar
pixhawk committed
2141 2142 2143 2144 2145
        result = name;
    }
    return result;
}

2146 2147 2148 2149 2150
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2151 2152 2153
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2154 2155 2156
    uint8_t modeid = id;

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

LM's avatar
LM committed
2158 2159 2160 2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179 2180
    // BASE MODE DECODING
    if (modeid & MAV_MODE_FLAG_DECODE_POSITION_AUTO)
    {
        mode = "AUTO";
    }
    else if (modeid & MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
    {
        mode = "GUIDED";
    }
    else if (modeid & MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
    {
        mode = "STABILIZED";
    }
    else if (modeid & MAV_MODE_FLAG_DECODE_POSITION_TEST)
    {
        mode = "TEST";
    }
    else if (modeid & MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
    {
        mode = "MANUAL";
    }
    else
    {
2181
        mode = "PREFLIGHT";
LM's avatar
LM committed
2182 2183 2184 2185 2186 2187 2188 2189 2190 2191 2192 2193 2194 2195 2196 2197
    }

    // ARMED STATE DECODING
    if (modeid & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
    {
        mode.prepend("A|");
    }
    else
    {
        mode.prepend("D|");
    }

    // HARDWARE IN THE LOOP DECODING
    if (modeid & MAV_MODE_FLAG_DECODE_POSITION_HIL)
    {
        mode.prepend("HIL:");
2198 2199 2200 2201 2202
    }

    return mode;
}

2203 2204 2205 2206 2207
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2208 2209
void UAS::addLink(LinkInterface* link)
{
2210 2211
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2212
        links->append(link);
2213
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2214 2215 2216
    }
}

2217 2218 2219
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2220 2221
    if (link)
    {
2222 2223 2224 2225
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2226 2227 2228 2229 2230 2231 2232 2233 2234 2235 2236 2237 2238 2239 2240
/**
 * @brief Get the links associated with this robot
 *
 **/
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}



void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2241 2242
    switch (batteryType)
    {
lm's avatar
lm committed
2243
    case NICD:
pixhawk's avatar
pixhawk committed
2244
        break;
lm's avatar
lm committed
2245
    case NIMH:
pixhawk's avatar
pixhawk committed
2246
        break;
lm's avatar
lm committed
2247
    case LIION:
pixhawk's avatar
pixhawk committed
2248
        break;
lm's avatar
lm committed
2249
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2250 2251 2252
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2253
    case LIFE:
pixhawk's avatar
pixhawk committed
2254
        break;
lm's avatar
lm committed
2255
    case AGZN:
pixhawk's avatar
pixhawk committed
2256 2257 2258 2259
        break;
    }
}

2260 2261
void UAS::setBatterySpecs(const QString& specs)
{
2262 2263
    if (specs.length() == 0 || specs.contains("%"))
    {
2264
        batteryRemainingEstimateEnabled = false;
2265
        bool ok;
2266 2267 2268
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2269 2270
        if (ok)
        {
2271
            warnLevelPercent = temp;
2272 2273 2274
        }
        else
        {
2275 2276
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2277 2278 2279
    }
    else
    {
2280 2281 2282 2283 2284
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2285 2286
        if (parts.length() == 3)
        {
2287 2288 2289 2290 2291 2292 2293 2294 2295 2296 2297
            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;
2298 2299 2300
        }
        else
        {
2301 2302
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2303 2304 2305 2306 2307
    }
}

QString UAS::getBatterySpecs()
{
2308 2309
    if (batteryRemainingEstimateEnabled)
    {
2310
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2311 2312 2313
    }
    else
    {
2314 2315
        return QString("%1%").arg(warnLevelPercent);
    }
2316 2317
}

pixhawk's avatar
pixhawk committed
2318 2319 2320 2321 2322 2323 2324 2325 2326 2327 2328 2329 2330
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
2331 2332 2333
/**
 * @return charge level in percent - 0 - 100
 */
2334
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2335
{
2336 2337 2338 2339
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2340
            chargeLevel = 0.0f;
2341 2342 2343
        }
        else if (lpVoltage > fullVoltage)
        {
2344
            chargeLevel = 100.0f;
2345 2346 2347
        }
        else
        {
2348 2349
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2350 2351
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2352 2353
}

lm's avatar
lm committed
2354 2355
void UAS::startLowBattAlarm()
{
2356 2357
    if (!lowBattAlarm)
    {
2358
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2359
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2360 2361 2362 2363 2364 2365
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2366 2367
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2368 2369 2370 2371
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}