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

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

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

30
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lm's avatar
lm committed
31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83
    uasId(id),
    startTime(QGC::groundTimeMilliseconds()),
    commStatus(COMM_DISCONNECTED),
    name(""),
    autopilot(-1),
    links(new QList<LinkInterface*>()),
    unknownPackets(),
    mavlink(protocol),
    waypointManager(this),
    thrustSum(0),
    thrustMax(10),
    startVoltage(0),
    warnVoltage(9.5f),
    warnLevelPercent(20.0f),
    currentVoltage(12.0f),
    lpVoltage(12.0f),
    batteryRemainingEstimateEnabled(true),
    mode(-1),
    status(-1),
    navMode(-1),
    onboardTimeOffset(0),
    controlRollManual(true),
    controlPitchManual(true),
    controlYawManual(true),
    controlThrustManual(true),
    manualRollAngle(0),
    manualPitchAngle(0),
    manualYawAngle(0),
    manualThrust(0),
    receiveDropRate(0),
    sendDropRate(0),
    lowBattAlarm(false),
    positionLock(false),
    localX(0.0),
    localY(0.0),
    localZ(0.0),
    latitude(0.0),
    longitude(0.0),
    altitude(0.0),
    roll(0.0),
    pitch(0.0),
    yaw(0.0),
    statusTimeout(new QTimer(this)),
    paramsOnceRequested(false),
    airframe(QGC_AIRFRAME_EASYSTAR),
    attitudeKnown(false),
    paramManager(NULL),
    attitudeStamped(false),
    lastAttitude(0),
    simulation(new QGCFlightGearLink(this)),
    isLocalPositionKnown(false),
    isGlobalPositionKnown(false),
    systemIsArmed(false)
pixhawk's avatar
pixhawk committed
84
{
85
    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
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
235 236 237
                    case MAV_TYPE_HEXAROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
                        break;
238 239 240 241 242
                    default:
                        // Do nothing
                        break;
                    }
                }
243
                this->autopilot = state.autopilot;
pixhawk's avatar
pixhawk committed
244 245
                emit systemTypeSet(this, type);
            }
246

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

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


271 272 273 274 275 276 277
            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);
278

279
                shortStateText = uasState;
280

281 282
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
283

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

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

292 293
                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed
294

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

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

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

324 325 326 327 328
//            if (state.system_status == MAV_STATE_POWEROFF)
//            {
//                emit systemRemoved(this);
//                emit systemRemoved();
//            }
329
}
330

331 332 333 334 335 336 337 338 339 340
            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);
341

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

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

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

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

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

382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397
//                // Emit in angles

//                // Convert yaw angle to compass value
//                // in 0 - 360 deg range
//                float compass = (yaw/M_PI)*180.0+360.0f;
//                if (compass > -10000 && compass < 10000)
//                {
//                    while (compass > 360.0f) {
//                        compass -= 360.0f;
//                    }
//                }
//                else
//                {
//                    // Set to 0, since it is an invalid value
//                    compass = 0.0f;
//                }
lm's avatar
lm committed
398

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

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

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

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

488 489
                if (pos.fix_type > 2)
                {
LM's avatar
LM committed
490 491 492 493 494
                    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;
495
                    isGlobalPositionKnown = true;
LM's avatar
LM committed
496 497 498

                    // Check for NaN
                    int alt = pos.alt;
499 500
                    if (!isnan(alt) && !isinf(alt))
                    {
LM's avatar
LM committed
501
                        alt = 0;
502
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE");
LM's avatar
LM committed
503
                    }
lm's avatar
lm committed
504
                    // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
LM's avatar
LM committed
505
                    // Smaller than threshold and not NaN
LM's avatar
LM committed
506 507 508

                    float vel = pos.vel/100.0f;

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

LM's avatar
LM committed
580
                // Insert component if necessary
581 582
                if (!parameters.contains(component))
                {
583
                    parameters.insert(component, new QMap<QString, QVariant>());
LM's avatar
LM committed
584
                }
585

LM's avatar
LM committed
586 587
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
588

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

lm's avatar
lm committed
665
        case MAVLINK_MSG_ID_MISSION_ITEM:
666
            {
lm's avatar
lm committed
667 668
                mavlink_mission_item_t wp;
                mavlink_msg_mission_item_decode(&message, &wp);
LM's avatar
LM committed
669
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
670
                if(wp.target_system == mavlink->getSystemId())
671
                {
LM's avatar
LM committed
672 673
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
LM's avatar
LM committed
674 675 676 677
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
678
            }
LM's avatar
LM committed
679
            break;
pixhawk's avatar
pixhawk committed
680

lm's avatar
lm committed
681
        case MAVLINK_MSG_ID_MISSION_ACK:
682
            {
lm's avatar
lm committed
683 684
                mavlink_mission_ack_t wpa;
                mavlink_msg_mission_ack_decode(&message, &wpa);
685 686
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
687 688
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
689
            }
LM's avatar
LM committed
690
            break;
691

lm's avatar
lm committed
692
        case MAVLINK_MSG_ID_MISSION_REQUEST:
693
            {
lm's avatar
lm committed
694 695
                mavlink_mission_request_t wpr;
                mavlink_msg_mission_request_decode(&message, &wpr);
696
                if(wpr.target_system == mavlink->getSystemId())
697
                {
LM's avatar
LM committed
698 699
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
LM's avatar
LM committed
700 701 702 703
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
704
            }
LM's avatar
LM committed
705
            break;
pixhawk's avatar
pixhawk committed
706

lm's avatar
lm committed
707
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
708
            {
lm's avatar
lm committed
709 710
                mavlink_mission_item_reached_t wpr;
                mavlink_msg_mission_item_reached_decode(&message, &wpr);
LM's avatar
LM committed
711 712 713 714 715 716
                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
717

lm's avatar
lm committed
718
        case MAVLINK_MSG_ID_MISSION_CURRENT:
719
            {
lm's avatar
lm committed
720 721
                mavlink_mission_current_t wpc;
                mavlink_msg_mission_current_decode(&message, &wpc);
LM's avatar
LM committed
722 723 724
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
725

726 727
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
728 729 730 731 732
                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;
733 734
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
735 736
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
lm's avatar
lm committed
737
                mavlink_msg_statustext_get_text(&message, b.data());
LM's avatar
LM committed
738 739 740 741 742 743 744 745
                //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;
746
#ifdef MAVLINK_ENABLED_PIXHAWK
747 748
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
749 750 751 752 753 754 755 756 757 758 759
                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;
760

761 762
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
763 764 765 766 767 768 769 770 771 772 773
                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;
774 775
                }

776 777
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
778 779 780 781 782
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
783

LM's avatar
LM committed
784
                ++imagePacketsArrived;
785

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

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

898
#endif
LM's avatar
LM committed
899
            // Messages to ignore
900
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
lm's avatar
lm committed
901 902 903 904 905 906 907
        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:
908
            break;
lm's avatar
lm committed
909
        case MAVLINK_MSG_ID_DEBUG_VECT:
LM's avatar
LM committed
910 911 912
            {
                mavlink_debug_vect_t debug;
                mavlink_msg_debug_vect_decode(&message, &debug);
913
                debug.name[MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN-1] = '\0';
LM's avatar
LM committed
914 915 916 917 918 919 920
                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
921
        case MAVLINK_MSG_ID_DEBUG:
922
            break;
923 924 925 926
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
927 928 929 930 931 932 933
                    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
934
            }
LM's avatar
LM committed
935
            break;
pixhawk's avatar
pixhawk committed
936 937 938 939
        }
    }
}

940 941
void UAS::setHomePosition(double lat, double lon, double alt)
{
942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974
    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);
    }
975 976
}

977 978 979 980 981 982 983 984 985 986 987 988 989 990
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()));


991 992
    if (ret == QMessageBox::Yes)
    {
993 994 995 996 997 998 999 1000
        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);
1001 1002 1003
    }
}

pixhawk's avatar
pixhawk committed
1004 1005
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1006
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1007
    mavlink_message_t msg;
LM's avatar
LM committed
1008
    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
1009
    sendMessage(msg);
1010
#else
lm's avatar
lm committed
1011 1012 1013 1014
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1015
#endif
pixhawk's avatar
pixhawk committed
1016 1017
}

pixhawk's avatar
pixhawk committed
1018 1019
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1020
#ifdef MAVLINK_ENABLED_PIXHAWK
1021
    mavlink_message_t msg;
1022
    mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
1023
    sendMessage(msg);
lm's avatar
lm committed
1024
#else
1025 1026 1027 1028
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1029 1030 1031 1032
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1033
{
1034 1035
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1036
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1, 0, 0, 0);
1037
    sendMessage(msg);
lm's avatar
lm committed
1038 1039
}

1040
void UAS::startDataRecording()
lm's avatar
lm committed
1041
{
1042
    mavlink_message_t msg;
1043
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2, 0, 0, 0);
1044
    sendMessage(msg);
lm's avatar
lm committed
1045 1046 1047 1048
}

void UAS::stopDataRecording()
{
1049
    mavlink_message_t msg;
1050
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0, 0, 0, 0);
1051
    sendMessage(msg);
lm's avatar
lm committed
1052 1053
}

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

void UAS::startGyroscopeCalibration()
{
1064 1065
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1066
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0, 0, 0, 0);
1067
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1068 1069 1070 1071
}

void UAS::startPressureCalibration()
{
1072 1073
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1074
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0, 0, 0, 0);
1075
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1076 1077
}

LM's avatar
LM committed
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 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122
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;
    }
}

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

1193 1194
QList<QString> UAS::getParameterNames(int component)
{
1195 1196
    if (parameters.contains(component))
    {
1197
        return parameters.value(component)->keys();
1198 1199 1200
    }
    else
    {
1201 1202 1203 1204 1205 1206 1207 1208 1209
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1210
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1211
{
LM's avatar
LM committed
1212 1213 1214 1215 1216
    //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
1217 1218 1219 1220 1221
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1222 1223 1224 1225
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1226
            sendMessage(link, message);
1227 1228 1229
        }
        else
        {
1230 1231 1232
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1233 1234 1235
    }
}

1236 1237 1238 1239
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1240

1241 1242 1243 1244
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1245
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1246 1247 1248 1249 1250 1251
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1252
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1253 1254
                        sendMessage(serial, message);
                    }
1255 1256 1257 1258 1259 1260
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1261 1262
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1263
    if(!link) return;
pixhawk's avatar
pixhawk committed
1264 1265 1266
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1267
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1268 1269
    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
1270
    // If link is connected
1271 1272
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1273 1274 1275 1276 1277 1278 1279 1280
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1281
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1282
{
1283
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1284 1285
}

1286 1287
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1288 1289
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
1290 1291
    switch (mode)
    {
lm's avatar
lm committed
1292
    case 0:
1293
        return QString("PREFLIGHT");
1294 1295 1296 1297
        break;
    default:
        return QString("UNKNOWN");
    }
lm's avatar
lm committed
1298 1299 1300 1301 1302 1303 1304 1305 1306
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1307 1308
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1309 1310
}

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

lm's avatar
lm committed
1348
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1349
        uasState = tr("SHUTDOWN");
1350
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1351
        break;
1352

lm's avatar
lm committed
1353
    default:
pixhawk's avatar
pixhawk committed
1354
        uasState = tr("UNKNOWN");
1355
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1356 1357 1358 1359
        break;
    }
}

1360 1361
QImage UAS::getImage()
{
LM's avatar
LM committed
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 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408
#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!";
        }
    }
1409 1410
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1411
    //imageRecBuffer.clear();
1412
    return image;
1413 1414
#else
	return QImage();
LM's avatar
LM committed
1415
#endif
1416

1417 1418 1419 1420
}

void UAS::requestImage()
{
1421
#ifdef MAVLINK_ENABLED_PIXHAWK
1422 1423
    qDebug() << "trying to get an image from the uas...";

1424 1425 1426
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1427 1428 1429 1430
        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);
    }
1431
#endif
1432
}
pixhawk's avatar
pixhawk committed
1433 1434 1435 1436 1437 1438 1439 1440 1441


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1442
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1443
{
1444 1445
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1446
        return 0;
1447 1448 1449
    }
    else
    {
pixhawk's avatar
pixhawk committed
1450 1451 1452 1453
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1454
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1455 1456 1457 1458
{
    return commStatus;
}

1459 1460 1461
void UAS::requestParameters()
{
    mavlink_message_t msg;
1462
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1463
    sendMessage(msg);
1464 1465
}

1466
void UAS::writeParametersToStorage()
1467
{
1468
    mavlink_message_t msg;
1469
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
pixhawk's avatar
pixhawk committed
1470
    qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
1471
    sendMessage(msg);
1472 1473 1474 1475
}

void UAS::readParametersFromStorage()
{
1476
    mavlink_message_t msg;
1477
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
1478
    sendMessage(msg);
lm's avatar
lm committed
1479 1480
}

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

1506
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1507 1508 1509
{
    // Buffers to write data to
    mavlink_message_t msg;
1510
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1511
    // Select the message to request from now on
1512
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1513
    // Select the update rate in Hz the message should be send
1514
    stream.req_message_rate = rate;
lm's avatar
lm committed
1515
    // Start / stop the message
1516
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1517 1518 1519 1520 1521
    // 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
1522
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1523 1524
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1525 1526
}

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

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

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

lm's avatar
lm committed
1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615
//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);
//}
1616

1617
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1618 1619 1620 1621 1622
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1623
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1624
    // Select the update rate in Hz the message should be send
1625
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1626
    // Start / stop the message
1627
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1628 1629 1630 1631 1632 1633 1634 1635 1636 1637
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
}

1638
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1639 1640 1641 1642 1643
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1644
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1645
    // Select the update rate in Hz the message should be send
1646
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1647
    // Start / stop the message
1648
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

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

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

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

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

        p.param_value = union_value.param_float;
1740 1741 1742
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

1743 1744
        qDebug() << "SENT PARAM:" << value;

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

1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782
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;
}

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

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

1822 1823
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
1824 1825 1826 1827 1828 1829 1830
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
1831 1832
}

lm's avatar
lm committed
1833 1834 1835
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
1836
    mavlink_command_long_t cmd;
1837 1838 1839 1840 1841 1842
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
1843 1844 1845
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
1846 1847
    cmd.target_system = uasId;
    cmd.target_component = 0;
1848
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1849 1850 1851 1852 1853 1854
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
1855
    mavlink_command_long_t cmd;
1856 1857 1858 1859 1860 1861
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1862 1863 1864
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
1865 1866
    cmd.target_system = uasId;
    cmd.target_component = component;
1867
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1868 1869 1870 1871 1872 1873 1874
    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;
1875 1876 1877 1878 1879 1880
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1881 1882 1883
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
1884 1885
    cmd.target_system = uasId;
    cmd.target_component = component;
1886
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
1887 1888 1889
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1890
/**
lm's avatar
lm committed
1891
 * Launches the system
pixhawk's avatar
pixhawk committed
1892 1893 1894 1895
 *
 **/
void UAS::launch()
{
1896
    mavlink_message_t msg;
1897
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_NAV_TAKEOFF, 1, 0, 0, 0, 0, 0, 0, 0);
1898
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1899 1900 1901 1902 1903 1904
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
1905
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
1906
{
1907
    mavlink_message_t msg;
1908
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
1909
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1910 1911 1912 1913 1914 1915
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
1916
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
1917
{
1918
    mavlink_message_t msg;
1919
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
1920
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934
}

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
1935 1936
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
1937
    {
1938 1939 1940 1941
        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
1942

1943
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
1944 1945 1946
    }
    else
    {
1947 1948
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
1949 1950
}

1951 1952 1953 1954 1955
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1956 1957
void UAS::receiveButton(int buttonIndex)
{
1958 1959
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
1960
    case 0:
pixhawk's avatar
pixhawk committed
1961

pixhawk's avatar
pixhawk committed
1962 1963
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1964

pixhawk's avatar
pixhawk committed
1965 1966 1967 1968 1969
        break;
    default:

        break;
    }
1970
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1971 1972 1973

}

1974

pixhawk's avatar
pixhawk committed
1975 1976
void UAS::halt()
{
1977 1978 1979
    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
1980 1981 1982 1983
}

void UAS::go()
{
1984 1985 1986
    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
1987 1988 1989 1990 1991
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1992 1993 1994 1995 1996 1997 1998 1999 2000
    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
2001 2002 2003 2004 2005 2006 2007 2008
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2009 2010
    // FIXME MAVLINKV10PORTINGNEEDED
    halt();
pixhawk's avatar
pixhawk committed
2011 2012 2013
}

/**
lm's avatar
lm committed
2014
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2015 2016 2017 2018 2019 2020
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
2021
    halt();
lm's avatar
lm committed
2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035 2036 2037 2038 2039 2040 2041 2042 2043 2044 2045 2046 2047
    // 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
2048 2049
}

lm's avatar
lm committed
2050 2051 2052 2053 2054
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2055
        startHil();
lm's avatar
lm committed
2056 2057 2058
    }
    else
    {
2059
        stopHil();
lm's avatar
lm committed
2060 2061 2062 2063 2064 2065 2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077 2078 2079 2080 2081 2082 2083 2084 2085 2086 2087 2088 2089 2090
    }
}

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


2091 2092
void UAS::startHil()
{
lm's avatar
lm committed
2093 2094
    // Connect Flight Gear Link
    simulation->connectSimulation();
2095
    mavlink_message_t msg;
LM's avatar
LM committed
2096
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
2097
    sendMessage(msg);
2098 2099
}

2100 2101
void UAS::stopHil()
{
lm's avatar
lm committed
2102
    simulation->disconnectSimulation();
2103
    mavlink_message_t msg;
LM's avatar
LM committed
2104
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
2105
    sendMessage(msg);
2106 2107 2108
}


pixhawk's avatar
pixhawk committed
2109 2110
void UAS::shutdown()
{
2111 2112 2113 2114 2115
    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
2116

2117 2118 2119
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2120

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

2124 2125 2126 2127
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2128
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 0, 2, 0, 0, 0, 0, 0);
2129 2130 2131
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2132 2133
}

2134 2135
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2136
    mavlink_message_t msg;
lm's avatar
lm committed
2137
    mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw);
2138
    sendMessage(msg);
2139 2140
}

pixhawk's avatar
pixhawk committed
2141 2142 2143
/**
 * @return The name of this system as string in human-readable form
 */
2144
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2145 2146
{
    QString result;
2147 2148
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2149
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2150 2151 2152
    }
    else
    {
pixhawk's avatar
pixhawk committed
2153 2154 2155 2156 2157
        result = name;
    }
    return result;
}

2158 2159 2160 2161 2162
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2163 2164 2165
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2166 2167 2168
    uint8_t modeid = id;

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

LM's avatar
LM committed
2170
    // BASE MODE DECODING
pixhawk's avatar
pixhawk committed
2171
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
LM's avatar
LM committed
2172
    {
pixhawk's avatar
pixhawk committed
2173
        mode += "AUTO";
LM's avatar
LM committed
2174
    }
pixhawk's avatar
pixhawk committed
2175
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
LM's avatar
LM committed
2176
    {
pixhawk's avatar
pixhawk committed
2177
        mode += "GUIDED";
LM's avatar
LM committed
2178
    }
pixhawk's avatar
pixhawk committed
2179
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
LM's avatar
LM committed
2180
    {
pixhawk's avatar
pixhawk committed
2181
        mode += "STABILIZED";
LM's avatar
LM committed
2182
    }
pixhawk's avatar
pixhawk committed
2183
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
LM's avatar
LM committed
2184
    {
pixhawk's avatar
pixhawk committed
2185
        mode += "TEST";
LM's avatar
LM committed
2186
    }
pixhawk's avatar
pixhawk committed
2187
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
LM's avatar
LM committed
2188
    {
pixhawk's avatar
pixhawk committed
2189
        mode += "MANUAL";
LM's avatar
LM committed
2190
    }
pixhawk's avatar
pixhawk committed
2191 2192

    if (modeid == 0)
LM's avatar
LM committed
2193
    {
2194
        mode = "PREFLIGHT";
LM's avatar
LM committed
2195 2196 2197
    }

    // ARMED STATE DECODING
pixhawk's avatar
pixhawk committed
2198
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
LM's avatar
LM committed
2199 2200 2201 2202 2203 2204 2205 2206 2207
    {
        mode.prepend("A|");
    }
    else
    {
        mode.prepend("D|");
    }

    // HARDWARE IN THE LOOP DECODING
pixhawk's avatar
pixhawk committed
2208
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
LM's avatar
LM committed
2209 2210
    {
        mode.prepend("HIL:");
2211 2212 2213 2214 2215
    }

    return mode;
}

2216 2217 2218 2219 2220
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2221 2222
void UAS::addLink(LinkInterface* link)
{
2223 2224
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2225
        links->append(link);
2226
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2227 2228 2229
    }
}

2230 2231 2232
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2233 2234
    if (link)
    {
2235 2236 2237 2238
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2239 2240 2241 2242 2243 2244 2245 2246 2247 2248 2249 2250 2251 2252 2253
/**
 * @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;
2254 2255
    switch (batteryType)
    {
lm's avatar
lm committed
2256
    case NICD:
pixhawk's avatar
pixhawk committed
2257
        break;
lm's avatar
lm committed
2258
    case NIMH:
pixhawk's avatar
pixhawk committed
2259
        break;
lm's avatar
lm committed
2260
    case LIION:
pixhawk's avatar
pixhawk committed
2261
        break;
lm's avatar
lm committed
2262
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2263 2264 2265
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2266
    case LIFE:
pixhawk's avatar
pixhawk committed
2267
        break;
lm's avatar
lm committed
2268
    case AGZN:
pixhawk's avatar
pixhawk committed
2269 2270 2271 2272
        break;
    }
}

2273 2274
void UAS::setBatterySpecs(const QString& specs)
{
2275 2276
    if (specs.length() == 0 || specs.contains("%"))
    {
2277
        batteryRemainingEstimateEnabled = false;
2278
        bool ok;
2279 2280 2281
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2282 2283
        if (ok)
        {
2284
            warnLevelPercent = temp;
2285 2286 2287
        }
        else
        {
2288 2289
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2290 2291 2292
    }
    else
    {
2293 2294 2295 2296 2297
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2298 2299
        if (parts.length() == 3)
        {
2300 2301 2302 2303 2304 2305 2306 2307 2308 2309 2310
            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;
2311 2312 2313
        }
        else
        {
2314 2315
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2316 2317 2318 2319 2320
    }
}

QString UAS::getBatterySpecs()
{
2321 2322
    if (batteryRemainingEstimateEnabled)
    {
2323
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2324 2325 2326
    }
    else
    {
2327 2328
        return QString("%1%").arg(warnLevelPercent);
    }
2329 2330
}

pixhawk's avatar
pixhawk committed
2331 2332 2333 2334 2335 2336 2337 2338 2339 2340 2341 2342 2343
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
2344 2345 2346
/**
 * @return charge level in percent - 0 - 100
 */
2347
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2348
{
2349 2350 2351 2352
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2353
            chargeLevel = 0.0f;
2354 2355 2356
        }
        else if (lpVoltage > fullVoltage)
        {
2357
            chargeLevel = 100.0f;
2358 2359 2360
        }
        else
        {
2361 2362
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2363 2364
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2365 2366
}

lm's avatar
lm committed
2367 2368
void UAS::startLowBattAlarm()
{
2369 2370
    if (!lowBattAlarm)
    {
2371
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2372
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2373 2374 2375 2376 2377 2378
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2379 2380
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2381 2382 2383 2384
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}