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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

LM's avatar
LM committed
205 206 207 208
    // Only accept messages from this system (condition 1)
    // and only then if a) attitudeStamped is disabled OR b) attitudeStamped is enabled
    // and we already got one attitude packet
    if (message.sysid == uasId && (!attitudeStamped || (attitudeStamped && (lastAttitude != 0)) || message.msgid == MAVLINK_MSG_ID_ATTITUDE))
209
    {
pixhawk's avatar
pixhawk committed
210 211
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
212

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

244 245 246 247 248 249 250 251 252 253 254 255 256 257 258
            bool currentlyArmed = state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;

            if (systemIsArmed != currentlyArmed)
            {
                systemIsArmed = currentlyArmed;
                emit armingChanged(systemIsArmed);
                if (systemIsArmed)
                {
                    emit armed();
                }
                else
                {
                    emit disarmed();
                }
            }
259

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


268 269 270 271 272 273 274
            if (state.system_status != this->status)
            {
                statechanged = true;
                this->status = state.system_status;
                getStatusForCode((int)state.system_status, uasState, stateDescription);
                emit statusChanged(this, uasState, stateDescription);
                emit statusChanged(this->status);
275

276
                shortStateText = uasState;
277

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

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

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

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

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

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

311 312 313 314 315 316 317
            if ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY)
            {
                GAudioOutput::instance()->startEmergency();
            }
            else if (modechanged || statechanged)
            {
                GAudioOutput::instance()->stopEmergency();
318
                GAudioOutput::instance()->say(audiostring.toLower());
319
            }
lm's avatar
lm committed
320

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

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

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


342

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

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

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

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

381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396
//                // 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
397

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

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

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

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

LM's avatar
LM committed
486
                if (pos.fix_type > 2) {
LM's avatar
LM committed
487 488 489 490 491 492 493 494 495 496 497 498
                    emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
                    latitude = pos.lat/(double)1E7;
                    longitude = pos.lon/(double)1E7;
                    altitude = pos.alt/1000.0;
                    positionLock = true;

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

                    float vel = pos.vel/100.0f;

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

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

LM's avatar
LM committed
578 579
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
580

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

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

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

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

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

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

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

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

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

LM's avatar
LM committed
776
                ++imagePacketsArrived;
777

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

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

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

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

969 970 971 972 973 974 975 976 977 978 979 980 981 982
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()));


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

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

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

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1025
{
1026 1027
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1028
    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);
1029
    sendMessage(msg);
lm's avatar
lm committed
1030 1031
}

1032
void UAS::startDataRecording()
lm's avatar
lm committed
1033
{
1034
    mavlink_message_t msg;
1035
    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);
1036
    sendMessage(msg);
lm's avatar
lm committed
1037 1038 1039 1040
}

void UAS::stopDataRecording()
{
1041
    mavlink_message_t msg;
1042
    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);
1043
    sendMessage(msg);
lm's avatar
lm committed
1044 1045
}

pixhawk's avatar
pixhawk committed
1046 1047
void UAS::startMagnetometerCalibration()
{
1048 1049
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1050
    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);
1051
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1052 1053 1054 1055
}

void UAS::startGyroscopeCalibration()
{
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, 1, 0, 0, 0, 0, 0, 0);
1059
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1060 1061 1062 1063
}

void UAS::startPressureCalibration()
{
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, 0, 0, 1, 0, 0, 0, 0);
1067
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1068 1069
}

LM's avatar
LM committed
1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114
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;
    }
}

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

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

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

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

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

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

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

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

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

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

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

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

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

1352 1353
QImage UAS::getImage()
{
LM's avatar
LM committed
1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400
#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!";
        }
    }
1401 1402
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1403
    //imageRecBuffer.clear();
1404
    return image;
1405 1406
#else
	return QImage();
LM's avatar
LM committed
1407
#endif
1408

1409 1410 1411 1412
}

void UAS::requestImage()
{
1413
#ifdef MAVLINK_ENABLED_PIXHAWK
1414 1415
    qDebug() << "trying to get an image from the uas...";

1416 1417 1418
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1419 1420 1421 1422
        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);
    }
1423
#endif
1424
}
pixhawk's avatar
pixhawk committed
1425 1426 1427 1428 1429 1430 1431 1432 1433


/* MANAGEMENT */

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

1446
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1447 1448 1449 1450
{
    return commStatus;
}

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

1458
void UAS::writeParametersToStorage()
1459
{
1460
    mavlink_message_t msg;
1461
    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
1462
    qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
1463
    sendMessage(msg);
1464 1465 1466 1467
}

void UAS::readParametersFromStorage()
{
1468
    mavlink_message_t msg;
1469
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
1470
    sendMessage(msg);
lm's avatar
lm committed
1471 1472
}

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

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

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

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

1566
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1567
{
1568 1569 1570 1571
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1572
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1573
    // Select the update rate in Hz the message should be send
1574
    stream.req_message_rate = rate;
1575
    // Start / stop the message
1576
    stream.start_stop = (rate) ? 1 : 0;
1577 1578 1579 1580 1581 1582
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1583 1584
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1585 1586
}

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

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

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

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

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

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

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

        p.param_value = union_value.param_float;
1732 1733 1734
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

1735 1736
        qDebug() << "SENT PARAM:" << value;

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

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
1882
/**
lm's avatar
lm committed
1883
 * Launches the system
pixhawk's avatar
pixhawk committed
1884 1885 1886 1887
 *
 **/
void UAS::launch()
{
1888
    mavlink_message_t msg;
1889
    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);
1890
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1891 1892 1893 1894 1895 1896
}

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

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

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
1927 1928
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
1929
    {
1930 1931 1932 1933
        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
1934

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

1943 1944 1945 1946 1947
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1948 1949
void UAS::receiveButton(int buttonIndex)
{
1950 1951
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
1952
    case 0:
pixhawk's avatar
pixhawk committed
1953

pixhawk's avatar
pixhawk committed
1954 1955
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1956

pixhawk's avatar
pixhawk committed
1957 1958 1959 1960 1961
        break;
    default:

        break;
    }
1962
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1963 1964 1965

}

1966

pixhawk's avatar
pixhawk committed
1967 1968
void UAS::halt()
{
1969 1970 1971
    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
1972 1973 1974 1975
}

void UAS::go()
{
1976 1977 1978
    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
1979 1980 1981 1982 1983
}

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

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

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

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

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


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

2092 2093
void UAS::stopHil()
{
lm's avatar
lm committed
2094
    simulation->disconnectSimulation();
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
}


pixhawk's avatar
pixhawk committed
2101 2102
void UAS::shutdown()
{
2103 2104 2105 2106 2107
    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
2108

2109 2110 2111
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2112

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

2116 2117 2118 2119
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2120
        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);
2121 2122 2123
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2124 2125
}

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

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

2150 2151 2152 2153 2154
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2155 2156 2157
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2158 2159 2160
    uint8_t modeid = id;

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

LM's avatar
LM committed
2162
    // BASE MODE DECODING
pixhawk's avatar
pixhawk committed
2163
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
LM's avatar
LM committed
2164
    {
pixhawk's avatar
pixhawk committed
2165
        mode += "AUTO";
LM's avatar
LM committed
2166
    }
pixhawk's avatar
pixhawk committed
2167
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
LM's avatar
LM committed
2168
    {
pixhawk's avatar
pixhawk committed
2169
        mode += "GUIDED";
LM's avatar
LM committed
2170
    }
pixhawk's avatar
pixhawk committed
2171
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
LM's avatar
LM committed
2172
    {
pixhawk's avatar
pixhawk committed
2173
        mode += "STABILIZED";
LM's avatar
LM committed
2174
    }
pixhawk's avatar
pixhawk committed
2175
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
LM's avatar
LM committed
2176
    {
pixhawk's avatar
pixhawk committed
2177
        mode += "TEST";
LM's avatar
LM committed
2178
    }
pixhawk's avatar
pixhawk committed
2179
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
LM's avatar
LM committed
2180
    {
pixhawk's avatar
pixhawk committed
2181
        mode += "MANUAL";
LM's avatar
LM committed
2182
    }
pixhawk's avatar
pixhawk committed
2183 2184

    if (modeid == 0)
LM's avatar
LM committed
2185
    {
2186
        mode = "PREFLIGHT";
LM's avatar
LM committed
2187 2188 2189
    }

    // ARMED STATE DECODING
pixhawk's avatar
pixhawk committed
2190
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
LM's avatar
LM committed
2191 2192 2193 2194 2195 2196 2197 2198 2199
    {
        mode.prepend("A|");
    }
    else
    {
        mode.prepend("D|");
    }

    // HARDWARE IN THE LOOP DECODING
pixhawk's avatar
pixhawk committed
2200
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
LM's avatar
LM committed
2201 2202
    {
        mode.prepend("HIL:");
2203 2204 2205 2206 2207
    }

    return mode;
}

2208 2209 2210 2211 2212
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2213 2214
void UAS::addLink(LinkInterface* link)
{
2215 2216
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2217
        links->append(link);
2218
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2219 2220 2221
    }
}

2222 2223 2224
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2225 2226
    if (link)
    {
2227 2228 2229 2230
        links->removeAt(links->indexOf(link));
    }
}

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

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

QString UAS::getBatterySpecs()
{
2313 2314
    if (batteryRemainingEstimateEnabled)
    {
2315
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2316 2317 2318
    }
    else
    {
2319 2320
        return QString("%1%").arg(warnLevelPercent);
    }
2321 2322
}

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

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

void UAS::stopLowBattAlarm()
{
2371 2372
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2373 2374 2375 2376
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}