UAS.cc 82.1 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
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),
47
batteryRemainingEstimateEnabled(true),
LM's avatar
LM committed
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
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),
75
airframe(QGC_AIRFRAME_EASYSTAR),
LM's avatar
LM committed
76
attitudeKnown(false),
LM's avatar
LM committed
77
paramManager(NULL),
LM's avatar
LM committed
78
attitudeStamped(false),
lm's avatar
lm committed
79
lastAttitude(0),
lm's avatar
lm committed
80
simulation(new QGCFlightGearLink(this)),
81
isLocalPositionKnown(false),
82 83
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
                // FIXME REMOVE LATER emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime());
341

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

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

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

                // Emit in angles

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

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

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

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

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

LM's avatar
LM committed
479
                if (pos.fix_type > 2) {
LM's avatar
LM committed
480 481 482 483 484 485 486 487 488 489 490 491
                    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
492
                    // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
LM's avatar
LM committed
493
                    // Smaller than threshold and not NaN
LM's avatar
LM committed
494 495 496 497

                    float vel = pos.vel/100.0f;

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

LM's avatar
LM committed
565
                // Insert component if necessary
566 567
                if (!parameters.contains(component))
                {
568
                    parameters.insert(component, new QMap<QString, QVariant>());
LM's avatar
LM committed
569
                }
570

LM's avatar
LM committed
571 572
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
573

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

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

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

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

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

lm's avatar
lm committed
703
        case MAVLINK_MSG_ID_MISSION_CURRENT:
704
            {
lm's avatar
lm committed
705 706
                mavlink_mission_current_t wpc;
                mavlink_msg_mission_current_decode(&message, &wpc);
LM's avatar
LM committed
707 708 709
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
710

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

746 747
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
748 749 750 751 752 753 754 755 756 757 758
                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;
759 760
                }

761 762
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
763 764 765 766 767
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
768

LM's avatar
LM committed
769
                ++imagePacketsArrived;
770

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

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

883
#endif
LM's avatar
LM committed
884
            // Messages to ignore
885
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
lm's avatar
lm committed
886 887 888 889 890 891 892 893
        case MAVLINK_MSG_ID_RAW_IMU:
        case MAVLINK_MSG_ID_SCALED_IMU:
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
        case MAVLINK_MSG_ID_RAW_PRESSURE:
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
        case MAVLINK_MSG_ID_OPTICAL_FLOW:
        case MAVLINK_MSG_ID_DEBUG_VECT:
LM's avatar
LM committed
894
        case MAVLINK_MSG_ID_DEBUG:
895
            break;
896 897 898 899
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
900 901 902 903 904 905 906
                    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
907
            }
LM's avatar
LM committed
908
            break;
pixhawk's avatar
pixhawk committed
909 910 911 912
        }
    }
}

913 914
void UAS::setHomePosition(double lat, double lon, double alt)
{
915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947
    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);
    }
948 949
}

950 951 952 953 954 955 956 957 958 959 960 961 962 963
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()));


964 965
    if (ret == QMessageBox::Yes)
    {
966 967 968 969 970 971 972 973
        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);
974 975 976
    }
}

pixhawk's avatar
pixhawk committed
977 978
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
979
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
980
    mavlink_message_t msg;
LM's avatar
LM committed
981
    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
982
    sendMessage(msg);
983
#else
lm's avatar
lm committed
984 985 986 987
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
988
#endif
pixhawk's avatar
pixhawk committed
989 990
}

pixhawk's avatar
pixhawk committed
991 992
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
993
#ifdef MAVLINK_ENABLED_PIXHAWK
994 995 996
    mavlink_message_t msg;
    mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
    sendMessage(msg);
lm's avatar
lm committed
997
#else
998 999 1000 1001
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1002 1003 1004 1005
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1006
{
1007 1008
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1009
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1);
1010
    sendMessage(msg);
lm's avatar
lm committed
1011 1012
}

1013
void UAS::startDataRecording()
lm's avatar
lm committed
1014
{
1015
    mavlink_message_t msg;
1016
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2);
1017
    sendMessage(msg);
lm's avatar
lm committed
1018 1019 1020 1021
}

void UAS::stopDataRecording()
{
1022
    mavlink_message_t msg;
1023
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0);
1024
    sendMessage(msg);
lm's avatar
lm committed
1025 1026
}

pixhawk's avatar
pixhawk committed
1027 1028
void UAS::startMagnetometerCalibration()
{
1029 1030
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1031
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0);
1032
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1033 1034 1035 1036
}

void UAS::startGyroscopeCalibration()
{
1037 1038
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1039
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0);
1040
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1041 1042 1043 1044
}

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

LM's avatar
LM committed
1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095
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;
    }
}

1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108
/**
 * @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
1109 1110 1111 1112 1113 1114 1115 1116
/**
 * @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!
 */
1117 1118
quint64 UAS::getUnixTime(quint64 time)
{
1119
    quint64 ret = 0;
LM's avatar
LM committed
1120 1121
    if (attitudeStamped)
    {
1122
        ret = lastAttitude;
LM's avatar
LM committed
1123
    }
1124 1125
    if (time == 0)
    {
1126
        ret = QGC::groundTimeMilliseconds();
1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143
    }
    // 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
1144
#ifndef _MSC_VER
1145
    else if (time < 1261440000000000LLU)
1146
#else
LM's avatar
LM committed
1147
        else if (time < 1261440000000000)
1148
#endif
LM's avatar
LM committed
1149 1150
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1151 1152
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1153
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1154
        }
1155
        ret = time/1000 + onboardTimeOffset;
1156 1157 1158
    }
    else
    {
1159 1160
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1161
        ret = time/1000;
1162
    }
1163
    return ret;
1164 1165
}

1166 1167
QList<QString> UAS::getParameterNames(int component)
{
1168 1169
    if (parameters.contains(component))
    {
1170
        return parameters.value(component)->keys();
1171 1172 1173
    }
    else
    {
1174 1175 1176 1177 1178 1179 1180 1181 1182
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1183
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1184
{
1185
    if (mode >= (int)MAV_MODE_PREFLIGHT && mode < (int)MAV_MODE_ENUM_END)
1186
    {
1187
        //this->mode = mode; //no call assignament, update receive message from UAS
pixhawk's avatar
pixhawk committed
1188
        mavlink_message_t msg;
1189
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode, (uint16_t)navMode);
pixhawk's avatar
pixhawk committed
1190
        sendMessage(msg);
lm's avatar
lm committed
1191
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
1192 1193 1194
    }
    else
    {
1195 1196
        qDebug() << "uas Mode not assign: " << mode;
    }
pixhawk's avatar
pixhawk committed
1197 1198 1199 1200 1201
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1202 1203 1204 1205
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1206
            sendMessage(link, message);
1207 1208 1209
        }
        else
        {
1210 1211 1212
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1213 1214 1215
    }
}

1216 1217 1218 1219
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1220

1221 1222 1223 1224
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1225
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1226 1227 1228 1229 1230 1231
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1232
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1233 1234
                        sendMessage(serial, message);
                    }
1235 1236 1237 1238 1239 1240
                }
            }
        }
    }
}

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

/**
 * @param value battery voltage
 */
1261
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1262
{
1263
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1264 1265
}

1266 1267
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1268 1269
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
1270 1271
    switch (mode)
    {
lm's avatar
lm committed
1272
    case 0:
1273
        return QString("PREFLIGHT");
1274 1275 1276 1277
        break;
    default:
        return QString("UNKNOWN");
    }
lm's avatar
lm committed
1278 1279 1280 1281 1282 1283 1284 1285 1286
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1287 1288
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1289 1290
}

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

lm's avatar
lm committed
1328
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1329
        uasState = tr("SHUTDOWN");
1330
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1331
        break;
1332

lm's avatar
lm committed
1333
    default:
pixhawk's avatar
pixhawk committed
1334
        uasState = tr("UNKNOWN");
1335
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1336 1337 1338 1339
        break;
    }
}

1340 1341
QImage UAS::getImage()
{
LM's avatar
LM committed
1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388
#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!";
        }
    }
1389 1390
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1391
    //imageRecBuffer.clear();
1392
    return image;
1393 1394
#else
	return QImage();
LM's avatar
LM committed
1395
#endif
1396

1397 1398 1399 1400
}

void UAS::requestImage()
{
1401
#ifdef MAVLINK_ENABLED_PIXHAWK
1402 1403
    qDebug() << "trying to get an image from the uas...";

1404 1405 1406
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1407 1408 1409 1410
        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);
    }
1411
#endif
1412
}
pixhawk's avatar
pixhawk committed
1413 1414 1415 1416 1417 1418 1419 1420 1421


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1422
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1423
{
1424 1425
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1426
        return 0;
1427 1428 1429
    }
    else
    {
pixhawk's avatar
pixhawk committed
1430 1431 1432 1433
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1434
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1435 1436 1437 1438
{
    return commStatus;
}

1439 1440 1441
void UAS::requestParameters()
{
    mavlink_message_t msg;
1442
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1443
    sendMessage(msg);
1444 1445
}

1446
void UAS::writeParametersToStorage()
1447
{
1448
    mavlink_message_t msg;
1449
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1);
1450
    sendMessage(msg);
1451 1452 1453 1454
}

void UAS::readParametersFromStorage()
{
1455
    mavlink_message_t msg;
1456
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1);
1457
    sendMessage(msg);
lm's avatar
lm committed
1458 1459
}

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

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

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

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

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

lm's avatar
lm committed
1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599
//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);
//}
1600

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

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

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

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

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

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

        p.param_value = union_value.param_float;
1725 1726 1727
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

1728 1729
        qDebug() << "SENT PARAM:" << value;

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

1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767
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;
}

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

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

1807 1808
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
1809 1810 1811 1812 1813 1814 1815
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
1816 1817
}

lm's avatar
lm committed
1818 1819 1820
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
1821
    mavlink_command_short_t cmd;
1822 1823 1824 1825 1826 1827 1828 1829
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
    cmd.target_system = uasId;
    cmd.target_component = 0;
1830
    mavlink_msg_command_short_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1831 1832 1833 1834 1835 1836
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
1837
    mavlink_command_short_t cmd;
1838 1839 1840 1841 1842 1843 1844 1845
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
    cmd.target_system = uasId;
    cmd.target_component = component;
1846 1847 1848 1849 1850 1851 1852 1853
    mavlink_msg_command_short_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component)
{
    mavlink_message_t msg;
    mavlink_command_long_t cmd;
1854 1855 1856 1857 1858 1859
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1860 1861 1862
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
1863 1864
    cmd.target_system = uasId;
    cmd.target_component = component;
1865
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
1866 1867 1868
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1869
/**
lm's avatar
lm committed
1870
 * Launches the system
pixhawk's avatar
pixhawk committed
1871 1872 1873 1874
 *
 **/
void UAS::launch()
{
1875 1876 1877
    mavlink_message_t msg;
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_NAV_TAKEOFF, 1, 0, 0, 0, 0);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1878 1879 1880 1881 1882 1883
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
1884
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
1885
{
1886
    mavlink_message_t msg;
1887
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
1888
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1889 1890 1891 1892 1893 1894
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
1895
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
1896
{
1897
    mavlink_message_t msg;
1898
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
1899
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1900 1901 1902 1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913
}

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
1914
    if(mode == (int)MAV_MODE_MANUAL_ARMED)
1915
    {
1916 1917 1918 1919
        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
1920

1921
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
1922 1923 1924
    }
    else
    {
1925 1926
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
1927 1928
}

1929 1930 1931 1932 1933
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1934 1935
void UAS::receiveButton(int buttonIndex)
{
1936 1937
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
1938
    case 0:
pixhawk's avatar
pixhawk committed
1939

pixhawk's avatar
pixhawk committed
1940 1941
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1942

pixhawk's avatar
pixhawk committed
1943 1944 1945 1946 1947
        break;
    default:

        break;
    }
1948
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1949 1950 1951

}

1952

pixhawk's avatar
pixhawk committed
1953 1954
void UAS::halt()
{
lm's avatar
lm committed
1955 1956 1957 1958 1959 1960 1961
    // FIXME MAVLINKV10PORTINGNEEDED
//    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_HALT);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1962 1963 1964 1965
}

void UAS::go()
{
lm's avatar
lm committed
1966 1967 1968 1969 1970 1971 1972
    // FIXME MAVLINKV10PORTINGNEEDED
//    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_CONTINUE);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1973 1974 1975 1976 1977
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
lm's avatar
lm committed
1978 1979 1980 1981 1982 1983 1984
    // FIXME MAVLINKV10PORTINGNEEDED
//    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_RETURN);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1985 1986 1987 1988 1989 1990 1991 1992
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
lm's avatar
lm committed
1993 1994 1995 1996 1997 1998 1999
//    mavlink_message_t msg;
//    // TODO Replace MG System ID with static function call and allow to change ID in GUI
//    // FIXME MAVLINKV10PORTINGNEEDED
//    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2000 2001 2002
}

/**
lm's avatar
lm committed
2003
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2004 2005 2006 2007 2008 2009
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
lm's avatar
lm committed
2010 2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035
    // FIXME MAVLINKV10PORTINGNEEDED
//    bool result = false;
//    QMessageBox msgBox;
//    msgBox.setIcon(QMessageBox::Critical);
//    msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS");
//    msgBox.setInformativeText("Do you want to cut power on all systems?");
//    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
//    msgBox.setDefaultButton(QMessageBox::Cancel);
//    int ret = msgBox.exec();

//    // Close the message box shortly after the click to prevent accidental clicks
//    QTimer::singleShot(5000, &msgBox, SLOT(reject()));


//    if (ret == QMessageBox::Yes)
//    {
//        mavlink_message_t msg;
//        // TODO Replace MG System ID with static function call and allow to change ID in GUI
//        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
//        // Send message twice to increase chance of reception
//        sendMessage(msg);
//        sendMessage(msg);
//        result = true;
//    }
//    return result;
    return false;
pixhawk's avatar
pixhawk committed
2036 2037
}

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

/**
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
*/
void UAS::sendHilState(uint64_t time_us, float roll, float pitch, float yaw, float rollspeed,
                    float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt,
                    int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
{
    mavlink_message_t msg;
    mavlink_msg_hil_state_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, time_us, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc);
    sendMessage(msg);
}


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

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


pixhawk's avatar
pixhawk committed
2097 2098
void UAS::shutdown()
{
lm's avatar
lm committed
2099 2100 2101 2102 2103 2104 2105 2106 2107 2108 2109 2110 2111 2112 2113 2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124
    // FIXME MAVLINKV10PORTINGNEEDED
//    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?");

//    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)
//    {
//        // If the active UAS is set, execute command
//        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_SHUTDOWN);
//        // Send message twice to increase chance of reception
//        sendMessage(msg);
//        sendMessage(msg);

//        result = true;
//    }
pixhawk's avatar
pixhawk committed
2125 2126
}

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

    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
2135 2136
}

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

2154 2155 2156 2157 2158
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2159 2160 2161 2162 2163 2164 2165 2166
QString UAS::getShortModeTextFor(int id)
{
    QString mode;

    switch (id) {
    case (uint8_t)MAV_MODE_PREFLIGHT:
        mode = "PREFLIGHT";
        break;
lm's avatar
lm committed
2167 2168 2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183
    case (uint8_t)MAV_MODE_MANUAL_ARMED:
        mode = "A|MANUAL";
        break;
    case (uint8_t)MAV_MODE_MANUAL_DISARMED:
        mode = "D|MANUAL";
        break;
    case (uint8_t)MAV_MODE_AUTO_ARMED:
        mode = "A|AUTO";
        break;
    case (uint8_t)MAV_MODE_AUTO_DISARMED:
        mode = "D|AUTO";
        break;
    case (uint8_t)MAV_MODE_GUIDED_ARMED:
        mode = "A|GUIDED";
        break;
    case (uint8_t)MAV_MODE_GUIDED_DISARMED:
        mode = "D|GUIDED";
2184
        break;
lm's avatar
lm committed
2185 2186
    case (uint8_t)MAV_MODE_STABILIZE_ARMED:
        mode = "A|STABILIZED";
2187
        break;
lm's avatar
lm committed
2188 2189
    case (uint8_t)MAV_MODE_STABILIZE_DISARMED:
        mode = "D|STABILIZED";
2190
        break;
lm's avatar
lm committed
2191 2192
    case (uint8_t)MAV_MODE_TEST_ARMED:
        mode = "A|TEST";
2193
        break;
lm's avatar
lm committed
2194 2195
    case (uint8_t)MAV_MODE_TEST_DISARMED:
        mode = "D|TEST";
2196 2197 2198 2199 2200 2201 2202 2203 2204
        break;
    default:
        mode = "UNKNOWN";
        break;
    }

    return mode;
}

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

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

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

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

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

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

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

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

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