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

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

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

30
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
31 32 33 34 35 36 37 38 39 40 41 42
uasId(id),
startTime(MG::TIME::getGroundTimeNow()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(-1),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
waypointManager(*this),
thrustSum(0),
thrustMax(10),
startVoltage(0),
pixhawk's avatar
pixhawk committed
43
warnVoltage(9.5f),
44
warnLevelPercent(20.0f),
45 46
currentVoltage(12.0f),
lpVoltage(12.0f),
47
batteryRemainingEstimateEnabled(false),
48 49 50
mode(-1),
status(-1),
navMode(-1),
51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73
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)),
74 75
paramsOnceRequested(false),
airframe(0)
pixhawk's avatar
pixhawk committed
76
{
77
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
78
    setBattery(LIPOLY, 3);
79
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
80
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
81
    statusTimeout->start(500);
82
    readSettings();
pixhawk's avatar
pixhawk committed
83 84 85 86
}

UAS::~UAS()
{
87
    writeSettings();
pixhawk's avatar
pixhawk committed
88
    delete links;
89
    links=NULL;
pixhawk's avatar
pixhawk committed
90 91
}

92 93 94 95 96
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
97 98
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
99
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
100 101 102 103 104 105 106 107 108
    settings.endGroup();
    settings.sync();
}

void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
109 110
    this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
    this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
111 112 113 114
    if (settings.contains("BATTERY_SPECS"))
    {
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
115 116 117
    settings.endGroup();
}

118
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
119 120 121 122
{
    return uasId;
}

123 124
void UAS::updateState()
{
125 126 127 128 129 130 131 132
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

133 134 135 136 137 138 139 140
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
    if (positionLock)
    {
        positionLock = false;
    }
    else
    {
pixhawk's avatar
pixhawk committed
141
        if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
142 143 144 145 146 147
        {
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
148 149
void UAS::setSelected()
{
150 151 152 153 154 155 156 157 158 159
    if (UASManager::instance()->getActiveUAS() != this)
    {
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

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

162 163 164 165
void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
    if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
    {
pixhawk's avatar
pixhawk committed
166 167
        mavlink_named_value_float_t val;
        mavlink_msg_named_value_float_decode(&message, &val);
lm's avatar
lm committed
168 169
        QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
        emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
170 171 172
    }
    else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
    {
pixhawk's avatar
pixhawk committed
173 174
        mavlink_named_value_int_t val;
        mavlink_msg_named_value_int_decode(&message, &val);
lm's avatar
lm committed
175 176
        QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN);
        emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
177 178 179
    }
}

pixhawk's avatar
pixhawk committed
180 181
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
182
    if (!link) return;
pixhawk's avatar
pixhawk committed
183 184 185
    if (!links->contains(link))
    {
        addLink(link);
186
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
187
    }
188 189 190 191
    //    else
    //    {
    //        qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
    //    }
pixhawk's avatar
pixhawk committed
192

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

pixhawk's avatar
pixhawk committed
195 196 197 198
    if (message.sysid == uasId)
    {
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
199

pixhawk's avatar
pixhawk committed
200 201 202
        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
203
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
204 205
            emit heartbeat(this);
            // Set new type if it has changed
pixhawk's avatar
pixhawk committed
206
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
207
            {
pixhawk's avatar
pixhawk committed
208
                this->type = mavlink_msg_heartbeat_get_type(&message);
209 210 211 212 213 214 215 216 217 218 219 220 221 222 223
                if (airframe == 0)
                {
                    switch (type)
                    {
                    case MAV_FIXED_WING:
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
                    case MAV_QUADROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
                    default:
                        // Do nothing
                        break;
                    }
                }
224
                this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
pixhawk's avatar
pixhawk committed
225 226
                emit systemTypeSet(this, type);
            }
227

228 229 230 231 232
            break;
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
            // Receive named value message
            receiveMessageNamedValue(message);
pixhawk's avatar
pixhawk committed
233 234 235 236 237 238
            break;
        case MAVLINK_MSG_ID_BOOT:
            getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);
            emit statusChanged(this, uasState, stateDescription);
            onboardTimeOffset = 0; // Reset offset measurement
            break;
pixhawk's avatar
pixhawk committed
239 240
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
241 242
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
243

pixhawk's avatar
pixhawk committed
244
                // FIXME
245
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
246

247
                QString audiostring = "System " + getUASName();
pixhawk's avatar
pixhawk committed
248 249 250 251
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
252

pixhawk's avatar
pixhawk committed
253
                if (state.status != this->status)
pixhawk's avatar
pixhawk committed
254
                {
pixhawk's avatar
pixhawk committed
255
                    statechanged = true;
256
                    this->status = state.status;
pixhawk's avatar
pixhawk committed
257 258
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
259
                    emit statusChanged(this->status);
260
                    stateAudio = " changed status to " + uasState;
pixhawk's avatar
pixhawk committed
261 262
                }

263 264 265 266 267 268
                if (navMode != state.nav_mode)
                {
                    emit navModeChanged(uasId, state.nav_mode, getNavModeText(state.nav_mode));
                    navMode = state.nav_mode;
                }

lm's avatar
lm committed
269
                emit loadChanged(this,state.load/10.0f);
lm's avatar
lm committed
270
                emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime());
lm's avatar
lm committed
271

272
                if (this->mode != static_cast<int>(state.mode))
pixhawk's avatar
pixhawk committed
273 274
                {
                    modechanged = true;
275
                    this->mode = static_cast<int>(state.mode);
pixhawk's avatar
pixhawk committed
276 277
                    QString mode;

lm's avatar
lm committed
278
                    switch (state.mode)
pixhawk's avatar
pixhawk committed
279
                    {
lm's avatar
lm committed
280
                    case (uint8_t)MAV_MODE_LOCKED:
pixhawk's avatar
pixhawk committed
281 282
                        mode = "LOCKED MODE";
                        break;
lm's avatar
lm committed
283
                    case (uint8_t)MAV_MODE_MANUAL:
pixhawk's avatar
pixhawk committed
284 285
                        mode = "MANUAL MODE";
                        break;
lm's avatar
lm committed
286
                    case (uint8_t)MAV_MODE_AUTO:
pixhawk's avatar
pixhawk committed
287 288
                        mode = "AUTO MODE";
                        break;
lm's avatar
lm committed
289
                    case (uint8_t)MAV_MODE_GUIDED:
290 291
                        mode = "GUIDED MODE";
                        break;
lm's avatar
lm committed
292
                    case (uint8_t)MAV_MODE_READY:
293
                        mode = "READY MODE";
lm's avatar
lm committed
294
                        break;
lm's avatar
lm committed
295
                    case (uint8_t)MAV_MODE_TEST1:
pixhawk's avatar
pixhawk committed
296 297
                        mode = "TEST1 MODE";
                        break;
lm's avatar
lm committed
298
                    case (uint8_t)MAV_MODE_TEST2:
pixhawk's avatar
pixhawk committed
299 300
                        mode = "TEST2 MODE";
                        break;
lm's avatar
lm committed
301
                    case (uint8_t)MAV_MODE_TEST3:
pixhawk's avatar
pixhawk committed
302 303
                        mode = "TEST3 MODE";
                        break;
lm's avatar
lm committed
304 305 306
                    case (uint8_t)MAV_MODE_RC_TRAINING:
                        mode = "RC TRAINING MODE";
                        break;
pixhawk's avatar
pixhawk committed
307 308 309 310 311 312 313 314
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }

                    emit modeChanged(this->getUASID(), mode, "");
                    modeAudio = " is now in " + mode;
                }
lm's avatar
lm committed
315
                currentVoltage = state.vbat/1000.0f;
pixhawk's avatar
pixhawk committed
316
                lpVoltage = filterVoltage(currentVoltage);
pixhawk's avatar
pixhawk committed
317 318
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
319 320 321 322
                if (!batteryRemainingEstimateEnabled)
                {
                    chargeLevel = state.battery_remaining/10.0f;
                }
pixhawk's avatar
pixhawk committed
323
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
pixhawk's avatar
pixhawk committed
324
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
pixhawk's avatar
pixhawk committed
325
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
pixhawk's avatar
pixhawk committed
326

lm's avatar
lm committed
327
                // LOW BATTERY ALARM
328
                if (lpVoltage < warnVoltage)
lm's avatar
lm committed
329 330 331 332 333 334 335 336
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
337
                // COMMUNICATIONS DROP RATE
lm's avatar
lm committed
338
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
339
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
340 341

                // AUDIO
pixhawk's avatar
pixhawk committed
342 343 344 345 346 347 348 349 350 351
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
352
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
pixhawk's avatar
pixhawk committed
353 354 355 356 357 358 359 360
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
361 362 363 364 365 366

                if (state.status == MAV_STATE_POWEROFF)
                {
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
pixhawk's avatar
pixhawk committed
367 368
            }
            break;
James Goppert's avatar
James Goppert committed
369 370

        #ifdef MAVLINK_ENABLED_PIXHAWK
371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386
        case MAVLINK_MSG_ID_CONTROL_STATUS:
            {
                mavlink_control_status_t status;
                mavlink_msg_control_status_decode(&message, &status);
                // Emit control status vector
                emit attitudeControlEnabled(static_cast<bool>(status.control_att));
                emit positionXYControlEnabled(static_cast<bool>(status.control_pos_xy));
                emit positionZControlEnabled(static_cast<bool>(status.control_pos_z));
                emit positionYawControlEnabled(static_cast<bool>(status.control_pos_yaw));

                // Emit localization status vector
                emit localizationChanged(this, status.position_fix);
                emit visionLocalizationChanged(this, status.vision_fix);
                emit gpsLocalizationChanged(this, status.gps_fix);
            }
            break;
lm's avatar
lm committed
387
#endif // PIXHAWK
pixhawk's avatar
pixhawk committed
388
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
389
            {
pixhawk's avatar
pixhawk committed
390 391
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
392
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
393

pixhawk's avatar
pixhawk committed
394 395 396
                emit valueChanged(uasId, "accel x", "raw", static_cast<double>(raw.xacc), time);
                emit valueChanged(uasId, "accel y", "raw", static_cast<double>(raw.yacc), time);
                emit valueChanged(uasId, "accel z", "raw", static_cast<double>(raw.zacc), time);
397 398 399
                emit valueChanged(uasId, "gyro roll", "raw", static_cast<double>(raw.xgyro), time);
                emit valueChanged(uasId, "gyro pitch", "raw", static_cast<double>(raw.ygyro), time);
                emit valueChanged(uasId, "gyro yaw", "raw", static_cast<double>(raw.zgyro), time);
pixhawk's avatar
pixhawk committed
400 401 402
                emit valueChanged(uasId, "mag x", "raw", static_cast<double>(raw.xmag), time);
                emit valueChanged(uasId, "mag y", "raw", static_cast<double>(raw.ymag), time);
                emit valueChanged(uasId, "mag z", "raw", static_cast<double>(raw.zmag), time);
pixhawk's avatar
pixhawk committed
403 404
            }
            break;
lm's avatar
lm committed
405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421
         case MAVLINK_MSG_ID_SCALED_IMU:
            {
                mavlink_scaled_imu_t scaled;
                mavlink_msg_scaled_imu_decode(&message, &scaled);
                quint64 time = getUnixTime(scaled.usec);

                emit valueChanged(uasId, "accel x", "g", scaled.xacc/1000.0f, time);
                emit valueChanged(uasId, "accel y", "g", scaled.yacc/1000.0f, time);
                emit valueChanged(uasId, "accel z", "g", scaled.zacc/1000.0f, time);
                emit valueChanged(uasId, "gyro roll", "rad/s", scaled.xgyro/1000.0f, time);
                emit valueChanged(uasId, "gyro pitch", "rad/s", scaled.ygyro/1000.0f, time);
                emit valueChanged(uasId, "gyro yaw", "rad/s", scaled.zgyro/1000.0f, time);
                emit valueChanged(uasId, "mag x", "tesla", scaled.xmag/1000.0f, time);
                emit valueChanged(uasId, "mag y", "tesla", scaled.ymag/1000.0f, time);
                emit valueChanged(uasId, "mag z", "tesla", scaled.zmag/1000.0f, time);
            }
            break;
pixhawk's avatar
pixhawk committed
422 423
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
424
            //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;
pixhawk's avatar
pixhawk committed
425
            {
pixhawk's avatar
pixhawk committed
426 427
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
428
                quint64 time = getUnixTime(attitude.usec);
429 430 431 432 433 434 435 436

                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);

                emit valueChanged(uasId, "roll", "rad", roll, time);
                emit valueChanged(uasId, "pitch", "rad", pitch, time);
                emit valueChanged(uasId, "yaw", "rad", yaw, time);
437 438 439
                emit valueChanged(uasId, "rollspeed", "rad/s", attitude.rollspeed, time);
                emit valueChanged(uasId, "pitchspeed", "rad/s", attitude.pitchspeed, time);
                emit valueChanged(uasId, "yawspeed", "rad/s", attitude.yawspeed, time);
440 441

                // Emit in angles
lm's avatar
lm committed
442

443 444 445 446
                // Convert yaw angle to compass value
                // in 0 - 360 deg range
                float compass = (yaw/M_PI)*180.0+360.0f;
                while (compass > 360.0f)
lm's avatar
lm committed
447
                {
448
                    compass -= 360.0f;
lm's avatar
lm committed
449 450
                }

451 452
                emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time);
pixhawk's avatar
pixhawk committed
453
                emit valueChanged(uasId, "heading deg", "deg", compass, time);
454 455 456
                emit valueChanged(uasId, "rollspeed d/s", "deg/s", (attitude.rollspeed/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitchspeed d/s", "deg/s", (attitude.pitchspeed/M_PI)*180.0, time);
                emit valueChanged(uasId, "yawspeed d/s", "deg/s", (attitude.yawspeed/M_PI)*180.0, time);
457

458 459
                emit attitudeChanged(this, roll, pitch, yaw, time);
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
460 461
            }
            break;
462 463 464 465 466 467 468 469 470 471 472
            case MAVLINK_MSG_ID_VFR_HUD:
            {
                mavlink_vfr_hud_t hud;
                mavlink_msg_vfr_hud_decode(&message, &hud);
                quint64 time = getUnixTime();
                // Display updated values
                emit valueChanged(uasId, "airspeed", "m/s", hud.airspeed, time);
                emit valueChanged(uasId, "groundspeed", "m/s", hud.groundspeed, time);
                emit valueChanged(uasId, "altitude", "m", hud.alt, time);
                emit valueChanged(uasId, "heading", "deg", hud.heading, time);
                emit valueChanged(uasId, "climbrate", "m/s", hud.climb, time);
473
                emit valueChanged(uasId, "throttle", "%", hud.throttle, time);
474
                emit thrustChanged(this, hud.throttle/100.0);
lm's avatar
lm committed
475
                emit altitudeChanged(uasId, hud.alt);
476 477
                //yaw = (hud.heading-180.0f/360.0f)*M_PI;
                //emit attitudeChanged(this, roll, pitch, yaw, getUnixTime());
lm's avatar
lm committed
478
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, getUnixTime());
479 480 481 482 483 484 485 486 487 488 489 490 491 492 493
            }
            break;
            case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
            {
                mavlink_nav_controller_output_t nav;
                mavlink_msg_nav_controller_output_decode(&message, &nav);
                quint64 time = getUnixTime();
                // Update UI
                emit valueChanged(uasId, "nav roll", "deg", nav.nav_roll, time);
                emit valueChanged(uasId, "nav pitch", "deg", nav.nav_pitch, time);
                emit valueChanged(uasId, "nav bearing", "deg", nav.nav_bearing, time);
                emit valueChanged(uasId, "target bearing", "deg", nav.target_bearing, time);
                emit valueChanged(uasId, "wp dist", "m", nav.wp_dist, time);
                emit valueChanged(uasId, "alt err", "m", nav.alt_error, time);
                emit valueChanged(uasId, "airspeed err", "m/s", nav.alt_error, time);
lm's avatar
lm committed
494
                emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time);
pixhawk's avatar
pixhawk committed
495 496
            }
            break;
497
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
498
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
499
            //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
500
            {
501 502
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
503
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
504 505 506
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
507 508 509 510 511 512
                emit valueChanged(uasId, "x", "m", pos.x, time);
                emit valueChanged(uasId, "y", "m", pos.y, time);
                emit valueChanged(uasId, "z", "m", pos.z, time);
                emit valueChanged(uasId, "x speed", "m/s", pos.vx, time);
                emit valueChanged(uasId, "y speed", "m/s", pos.vy, time);
                emit valueChanged(uasId, "z speed", "m/s", pos.vz, time);
lm's avatar
lm committed
513
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
514
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
515

516 517
                //                qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
                //                qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
518

519
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
520 521 522 523 524 525 526
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
527 528
            }
            break;
529
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
530 531 532
            //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;
            {
533 534
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
535
                quint64 time = QGC::groundTimeUsecs()/1000;
536 537 538 539 540 541
                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;
542 543 544
                emit valueChanged(uasId, "latitude", "deg", latitude, time);
                emit valueChanged(uasId, "longitude", "deg", longitude, time);
                emit valueChanged(uasId, "altitude", "m", altitude, time);
545 546
                double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
                emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
547
                emit globalPositionChanged(this, latitude, longitude, altitude, time);
548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573
                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;
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
            }
            break;
        case MAVLINK_MSG_ID_GLOBAL_POSITION:
            {
                mavlink_global_position_t pos;
                mavlink_msg_global_position_decode(&message, &pos);
                quint64 time = QGC::groundTimeUsecs()/1000;
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
                speedX = pos.vx;
                speedY = pos.vy;
                speedZ = pos.vz;
                emit valueChanged(uasId, "latitude", "deg", latitude, time);
                emit valueChanged(uasId, "longitude", "deg", longitude, time);
                emit valueChanged(uasId, "altitude", "m", altitude, time);
574 575
                double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
                emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
576
                emit globalPositionChanged(this, latitude, longitude, altitude, time);
577
                emit speedChanged(this, speedX, speedY, speedZ, time);
pixhawk's avatar
pixhawk committed
578 579 580 581 582 583 584
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
585 586
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
587 588 589 590 591 592 593 594
            }
            break;
        case MAVLINK_MSG_ID_GPS_RAW:
            //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;
            {
                mavlink_gps_raw_t pos;
                mavlink_msg_gps_raw_decode(&message, &pos);
595 596 597

                // SANITY CHECK
                // only accept values in a realistic range
598
                // quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
599
                quint64 time = getUnixTime();
lm's avatar
lm committed
600

601 602
                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
lm's avatar
lm committed
603

lm's avatar
lm committed
604
                if (pos.fix_type > 0)
605
                {
606
                    emit globalPositionChanged(this, pos.lat, pos.lon, pos.alt, time);
607
                    emit valueChanged(uasId, "gps speed", "m/s", pos.v, time);
608 609 610
                    latitude = pos.lat;
                    longitude = pos.lon;
                    altitude = pos.alt;
lm's avatar
lm committed
611
                    positionLock = true;
lm's avatar
lm committed
612 613 614 615 616 617 618 619

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
620
                    emit valueChanged(uasId, "altitude", "m", pos.alt, time);
lm's avatar
lm committed
621 622 623
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
624
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
lm's avatar
lm committed
625
                        //qDebug() << "GOT GPS RAW";
626
                       // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
lm's avatar
lm committed
627 628 629 630 631
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
632
                }
633 634
            }
            break;
635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);

                // SANITY CHECK
                // only accept values in a realistic range
                // quint64 time = getUnixTime(pos.usec);
                quint64 time = getUnixTime();

                emit valueChanged(uasId, "latitude", "deg", pos.lat/(double)1E7, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon/(double)1E7, time);

                if (pos.fix_type > 0)
                {
                    emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
                    emit valueChanged(uasId, "gps speed", "m/s", pos.v, time);
652 653 654
                    latitude = pos.lat/(double)1E7;
                    longitude = pos.lon/(double)1E7;
                    altitude = pos.alt/1000.0;
lm's avatar
lm committed
655
                    positionLock = true;
656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
                    emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E7, time);
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
                        //qDebug() << "GOT GPS RAW";
                       // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
                }
            }
            break;
lm's avatar
lm committed
679 680 681 682
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
683
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
684
                {
lm's avatar
lm committed
685
                    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]));
lm's avatar
lm committed
686 687 688
                }
            }
            break;
689 690 691 692 693 694 695
        case MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET:
            {
                mavlink_gps_local_origin_set_t pos;
                mavlink_msg_gps_local_origin_set_decode(&message, &pos);
                // FIXME Emit to other components
            }
            break;
696 697 698 699
            case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
700
                quint64 time = this->getUnixTime(pressure.usec);
701 702 703
                emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
                emit valueChanged(uasId, "diff pressure 1", "hPa", pressure.press_diff1, time);
                emit valueChanged(uasId, "diff pressure 2", "hPa", pressure.press_diff2, time);
704
                emit valueChanged(uasId, "temperature", "deg C", pressure.temperature/100.0f, time);
705 706
            }
            break;
707
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
708
            {
709 710
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
711
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734
                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;
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
                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
735 736
            }
            break;
737 738 739 740
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
741 742
                QByteArray bytes((char*)value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
                QString parameterName = QString(bytes);
743 744 745 746 747 748 749 750 751 752 753 754 755 756 757
                int component = message.compid;
                float val = value.param_value;

                // Insert component if necessary
                if (!parameters.contains(component))
                {
                    parameters.insert(component, new QMap<QString, float>());
                }

                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
                parameters.value(component)->insert(parameterName, val);

                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, val);
lm's avatar
lm committed
758 759 760 761 762 763 764 765 766 767 768 769 770
                emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val);
            }
            break;
        case MAVLINK_MSG_ID_ACTION_ACK:
            mavlink_action_ack_t ack;
            mavlink_msg_action_ack_decode(&message, &ack);
            if (ack.result == 1)
            {
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed action: %1").arg(ack.action));
            }
            else
            {
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected action: %1").arg(ack.action));
771 772
            }
            break;
pixhawk's avatar
pixhawk committed
773
        case MAVLINK_MSG_ID_DEBUG:
774
            emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), "raw", mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow());
pixhawk's avatar
pixhawk committed
775
            break;
776 777 778 779 780
        case MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT:
            {
                mavlink_attitude_controller_output_t out;
                mavlink_msg_attitude_controller_output_decode(&message, &out);
                quint64 time = MG::TIME::getGroundTimeNowUsecs();
lm's avatar
lm committed
781
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
782 783 784
                emit valueChanged(uasId, "att control roll", "raw", out.roll, time/1000.0f);
                emit valueChanged(uasId, "att control pitch", "raw", out.pitch, time/1000.0f);
                emit valueChanged(uasId, "att control yaw", "raw", out.yaw, time/1000.0f);
785 786 787 788 789 790
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
791
                quint64 time = MG::TIME::getGroundTimeNow();
792
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
793 794 795
                emit valueChanged(uasId, "pos control x", "raw", out.x, time);
                emit valueChanged(uasId, "pos control y", "raw", out.y, time);
                emit valueChanged(uasId, "pos control z", "raw", out.z, time);
796 797
            }
            break;
pixhawk's avatar
pixhawk committed
798 799 800 801
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
802 803 804 805
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
806 807 808
            }
            break;

809
        case MAVLINK_MSG_ID_WAYPOINT:
810
            {
811 812
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
813
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
814 815 816 817
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
818
            }
pixhawk's avatar
pixhawk committed
819
            break;
pixhawk's avatar
pixhawk committed
820

821 822 823 824 825 826 827 828 829 830 831
        case MAVLINK_MSG_ID_WAYPOINT_ACK:
            {
                mavlink_waypoint_ack_t wpa;
                mavlink_msg_waypoint_ack_decode(&message, &wpa);
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
            }
            break;

pixhawk's avatar
pixhawk committed
832 833 834 835
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
836 837 838 839
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
840 841 842
            }
            break;

843
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
844
            {
pixhawk's avatar
pixhawk committed
845 846 847
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
848 849 850
                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);
851
            }
pixhawk's avatar
pixhawk committed
852
            break;
pixhawk's avatar
pixhawk committed
853

854
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
855
            {
856 857 858
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
859
            }
pixhawk's avatar
pixhawk committed
860
            break;
pixhawk's avatar
pixhawk committed
861

862 863 864 865 866 867 868
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
                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;
869 870 871 872 873 874 875 876 877 878 879 880 881 882 883
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
            {
                mavlink_servo_output_raw_t servos;
                mavlink_msg_servo_output_raw_decode(&message, &servos);
                quint64 time = getUnixTime(0);
                emit valueChanged(uasId, "servo #1", "us", servos.servo1_raw, time);
                emit valueChanged(uasId, "servo #2", "us", servos.servo2_raw, time);
                emit valueChanged(uasId, "servo #3", "us", servos.servo3_raw, time);
                emit valueChanged(uasId, "servo #4", "us", servos.servo4_raw, time);
                emit valueChanged(uasId, "servo #5", "us", servos.servo5_raw, time);
                emit valueChanged(uasId, "servo #6", "us", servos.servo6_raw, time);
                emit valueChanged(uasId, "servo #7", "us", servos.servo7_raw, time);
                emit valueChanged(uasId, "servo #8", "us", servos.servo8_raw, time);
            }
            break;
884
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
885 886
            {
                QByteArray b;
lm's avatar
lm committed
887
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
pixhawk's avatar
pixhawk committed
888
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
889 890
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
891
                int severity = mavlink_msg_statustext_get_severity(&message);
892
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
893
                //emit statusTextReceived(severity, text);
894
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
895 896
            }
            break;
897 898 899 900 901 902 903 904 905 906

        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
                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;
lm's avatar
lm committed
907
                imageStart = QGC::groundTimeMilliseconds();
908 909 910 911 912 913 914 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
            }
            break;

        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
                mavlink_encapsulated_data_t img;
                mavlink_msg_encapsulated_data_decode(&message, &img);
                int seq = img.seqnr;
                int pos = seq * imagePayload;

                for (int i = 0; i < imagePayload; ++i)
                {
                    if (pos <= imageSize)
                    {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }

                ++imagePacketsArrived;

                // emit signal if all packets arrived
                if ((imagePacketsArrived == imagePackets))
                {
                    image.loadFromData(imageRecBuffer);
                    emit imageReady(this);
                    // Restart statemachine
                    imagePacketsArrived = 0;

                    //this->requestImage();
                    //qDebug() << "SENDING REQUEST TO GET NEW IMAGE FROM SYSTEM" << uasId;
                }
            }
            break;

        case MAVLINK_MSG_ID_DEBUG_VECT:
944 945 946 947 948
            {
                mavlink_debug_vect_t vect;
                mavlink_msg_debug_vect_decode(&message, &vect);
                QString str((const char*)vect.name);
                quint64 time = getUnixTime(vect.usec);
949 950 951
                emit valueChanged(uasId, str+".x", "raw", vect.x, time);
                emit valueChanged(uasId, str+".y", "raw", vect.y, time);
                emit valueChanged(uasId, str+".z", "raw", vect.z, time);
952 953
            }
            break;
954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969
            //#ifdef MAVLINK_ENABLED_PIXHAWK
            //            case MAVLINK_MSG_ID_POINT_OF_INTEREST:
            //            {
            //                mavlink_point_of_interest_t poi;
            //                mavlink_msg_point_of_interest_decode(&message, &poi);
            //                emit poiFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN), poi.x, poi.y, poi.z);
            //            }
            //            break;
            //            case MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION:
            //            {
            //                mavlink_point_of_interest_connection_t poi;
            //                mavlink_msg_point_of_interest_connection_decode(&message, &poi);
            //                emit poiConnectionFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN), poi.x1, poi.y1, poi.z1, poi.x2, poi.y2, poi.z2);
            //            }
            //            break;
            //#endif
lm's avatar
lm committed
970
#ifdef MAVLINK_ENABLED_UALBERTA
971 972 973 974 975
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = MG::TIME::getGroundTimeNow();
976 977 978 979 980 981
                emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time);
                emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time);
                emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time);
                emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time);
                emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time);
                emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time);
982 983
            }
            break;
984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007
       case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
                QVector<float> aileron;
                QVector<float> elevator;
                QVector<float> rudder;
                QVector<float> gyro;
                QVector<float> pitch;
                QVector<float> throttle;

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

1008
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
1009 1010 1011 1012 1013
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

1014
#endif
1015 1016 1017
            // Messages to ignore
            case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
            break;
pixhawk's avatar
pixhawk committed
1018
        default:
lm's avatar
lm committed
1019 1020 1021 1022
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
1023
                    QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid);
1024 1025
                    GAudioOutput::instance()->say(errString+tr(", please check the communication console for details."));
                    emit textMessageReceived(uasId, message.compid, 255, errString);
1026
                    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;
lm's avatar
lm committed
1027 1028 1029
                    //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;
                }
            }
pixhawk's avatar
pixhawk committed
1030 1031 1032 1033 1034
            break;
        }
    }
}

1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064
void UAS::setLocalOriginAtCurrentGPSPosition()
{

    bool result = false;
    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_action_pack(mavlink->getSystemId(), mavlink->getSystemId(), &msg, this->getUASID(), 0, MAV_ACTION_SET_ORIGIN);
        // Send message twice to increase chance that it reaches its goal
        sendMessage(msg);
        // Wait 5 ms
        MG::SLEEP::usleep(5000);
        // Send again
        sendMessage(msg);
        result = true;
    }
}

pixhawk's avatar
pixhawk committed
1065 1066
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1067
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1068
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1069 1070
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
1071
#else
lm's avatar
lm committed
1072 1073 1074 1075
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1076
#endif
pixhawk's avatar
pixhawk committed
1077 1078
}

pixhawk's avatar
pixhawk committed
1079 1080
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1081
#ifdef MAVLINK_ENABLED_PIXHAWK
1082 1083 1084
    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
1085
#else
1086 1087 1088 1089
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1090 1091 1092 1093 1094
#endif
}

void UAS::startRadioControlCalibration()
{
1095 1096 1097
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_RC);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1098 1099
}

lm's avatar
lm committed
1100 1101
void UAS::startDataRecording()
{
1102 1103 1104
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_START);
    sendMessage(msg);
lm's avatar
lm committed
1105 1106 1107 1108
}

void UAS::pauseDataRecording()
{
1109 1110 1111
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_PAUSE);
    sendMessage(msg);
lm's avatar
lm committed
1112 1113 1114 1115
}

void UAS::stopDataRecording()
{
1116 1117 1118
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_STOP);
    sendMessage(msg);
lm's avatar
lm committed
1119 1120
}

pixhawk's avatar
pixhawk committed
1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141
void UAS::startMagnetometerCalibration()
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_MAG);
    sendMessage(msg);
}

void UAS::startGyroscopeCalibration()
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_GYRO);
    sendMessage(msg);
}

void UAS::startPressureCalibration()
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_PRESSURE);
    sendMessage(msg);
}

1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163
quint64 UAS::getUnixTime(quint64 time)
{
    if (time == 0)
    {
        return MG::TIME::getGroundTimeNow();
    }
    // 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
1164
#ifndef _MSC_VER
1165
    else if (time < 1261440000000000LLU)
1166
#else
1167
        else if (time < 1261440000000000)
1168
#endif
1169
        {
1170 1171
        if (onboardTimeOffset == 0)
        {
1172
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
1173
        }
1174
        return time/1000 + onboardTimeOffset;
1175 1176 1177 1178 1179
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1180
        return time/1000;
1181 1182 1183
    }
}

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

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

pixhawk's avatar
pixhawk committed
1201
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1202
{
lm's avatar
lm committed
1203
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
1204
    {
1205
        this->mode = mode;
pixhawk's avatar
pixhawk committed
1206
        mavlink_message_t msg;
lm's avatar
lm committed
1207
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
1208
        sendMessage(msg);
lm's avatar
lm committed
1209
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
1210
    }
pixhawk's avatar
pixhawk committed
1211 1212 1213 1214 1215
}

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

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

1235 1236
    foreach(LinkInterface* link, link_list)
    {
1237
        if (link)
1238
        {
1239 1240
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
            if(serial != 0)
1241
            {
1242 1243

                for(int i=0;i<links->size();i++)
1244
                {
1245 1246
                    if(serial != links->at(i))
                    {
1247
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1248 1249
                        sendMessage(serial, message);
                    }
1250 1251 1252 1253 1254 1255
                }
            }
        }
    }
}

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

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

1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315
QString UAS::getNavModeText(int mode)
{
    switch (mode)
    {
    case MAV_NAV_GROUNDED:
        return QString("GROUNDED");
        break;
    case MAV_NAV_HOLD:
        return QString("HOLD");
        break;
    case MAV_NAV_LANDING:
        return QString("LANDING");
        break;
    case MAV_NAV_LIFTOFF:
        return QString("LIFTOFF");
        break;
    case MAV_NAV_LOITER:
        return QString("LOITER");
        break;
    case MAV_NAV_LOST:
        return QString("LOST");
        break;
    case MAV_NAV_RETURNING:
        return QString("RETURNING");
        break;
    case MAV_NAV_VECTOR:
        return QString("VECTOR");
        break;
    case MAV_NAV_WAYPOINT:
        return QString("WAYPOINT");
        break;
    default:
        return QString("UNKNOWN");
    }
}

pixhawk's avatar
pixhawk committed
1316 1317 1318 1319
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
1320
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1321
        uasState = tr("UNINIT");
1322
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1323
        break;
lm's avatar
lm committed
1324
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1325
        uasState = tr("BOOT");
1326
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1327
        break;
lm's avatar
lm committed
1328
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1329
        uasState = tr("CALIBRATING");
1330
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1331
        break;
lm's avatar
lm committed
1332
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1333
        uasState = tr("ACTIVE");
1334
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1335
        break;
lm's avatar
lm committed
1336 1337
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1338
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1339 1340
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1341
        uasState = tr("CRITICAL");
1342
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1343
        break;
lm's avatar
lm committed
1344
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1345
        uasState = tr("EMERGENCY");
1346
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1347
        break;
lm's avatar
lm committed
1348
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1349
        uasState = tr("SHUTDOWN");
1350
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1351
        break;
lm's avatar
lm committed
1352
    default:
pixhawk's avatar
pixhawk committed
1353
        uasState = tr("UNKNOWN");
1354
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1355 1356 1357 1358
        break;
    }
}

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
QImage UAS::getImage()
{
    return image;
}

void UAS::requestImage()
{
    qDebug() << "trying to get an image from the uas...";

    if (imagePacketsArrived == 0)
    {
        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);
    }
    else if (MG::TIME::getGroundTimeNow() - imageStart >= 1000)
    {
        // handshake happened more than 1 second ago, packets should have arrived by now
        // maybe we missed some packets (dropped along the way)
        image.loadFromData(imageRecBuffer);
        emit imageReady(this);
        // Restart statemachine
        imagePacketsArrived = 0;
    }
    // default else, wait?
}
pixhawk's avatar
pixhawk committed
1385 1386 1387 1388 1389 1390 1391 1392 1393


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1394
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1395 1396 1397 1398 1399 1400 1401 1402
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1403
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1404 1405 1406 1407
{
    return commStatus;
}

1408 1409 1410
void UAS::requestParameters()
{
    mavlink_message_t msg;
1411
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1412 1413
    // Send message twice to increase chance of reception
    sendMessage(msg);
1414 1415
}

1416
void UAS::writeParametersToStorage()
1417
{
1418 1419 1420
    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, (uint8_t)MAV_ACTION_STORAGE_WRITE);
unknown's avatar
unknown committed
1421
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1422 1423 1424 1425 1426 1427 1428 1429 1430
    sendMessage(msg);
}

void UAS::readParametersFromStorage()
{
    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,(uint8_t)MAV_ACTION_STORAGE_READ);
    sendMessage(msg);
lm's avatar
lm committed
1431 1432
}

1433
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1434 1435
{
    // Buffers to write data to
1436
    mavlink_message_t msg;
1437
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1438 1439
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1440
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1441 1442
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1443 1444
    // 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
1445 1446
    stream.req_message_rate = 0;
    // Start / stop the message
1447
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1448 1449 1450 1451 1452
    // 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
1453
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1454 1455
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1456 1457 1458
    sendMessage(msg);
}

1459
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1460 1461 1462
{
    // Buffers to write data to
    mavlink_message_t msg;
1463
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1464
    // Select the message to request from now on
1465
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1466
    // Select the update rate in Hz the message should be send
1467
    stream.req_message_rate = rate;
lm's avatar
lm committed
1468
    // Start / stop the message
1469
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1470 1471 1472 1473 1474
    // 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
1475
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1476 1477
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1478 1479 1480
    sendMessage(msg);
}

1481
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1482
{
1483 1484 1485 1486
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1487
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1488
    // Select the update rate in Hz the message should be send
1489
    stream.req_message_rate = rate;
1490
    // Start / stop the message
1491
    stream.start_stop = (rate) ? 1 : 0;
1492 1493 1494 1495 1496 1497
    // 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);
1498 1499
    // Send message twice to increase chance of reception
    sendMessage(msg);
1500
    sendMessage(msg);
lm's avatar
lm committed
1501
}
1502

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

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

lm's avatar
lm committed
1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572
//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);
//}
1573

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

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

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

1640
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1641 1642 1643 1644 1645
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1646
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1647
    // Select the update rate in Hz the message should be send
1648
    stream.req_message_rate = rate;
1649
    // Start / stop the message
1650
    stream.start_stop = (rate) ? 1 : 0;
1651 1652 1653 1654 1655 1656
    // 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);
1657 1658
    // Send message twice to increase chance of reception
    sendMessage(msg);
1659
    sendMessage(msg);
1660 1661
}

lm's avatar
lm committed
1662 1663 1664 1665 1666 1667 1668
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
lm's avatar
lm committed
1669 1670 1671 1672
void UAS::setParameter(const int component, const QString& id, const float value)
{
    if (!id.isNull())
    {
1673 1674 1675
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1676 1677
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1678

1679
    // Copy string into buffer, ensuring not to exceed the buffer size    
1680
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1681
    {
lm's avatar
lm committed
1682
        // String characters
1683
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1684
        {
1685
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1686
        }
1687 1688 1689 1690 1691
//        // 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';
//        }
lm's avatar
lm committed
1692 1693 1694 1695 1696
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1697
    }    
1698
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1699
    sendMessage(msg);
lm's avatar
lm committed
1700
    }
1701 1702
}

1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714
void UAS::requestParameter(int component, int parameter)
{
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
    read.param_index = parameter;
    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" << parameter;
}

1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
    if (airframe == 0)
    {
        switch (systemType)
        {
        case MAV_FIXED_WING:
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
        case MAV_QUADROTOR:
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1734 1735 1736
void UAS::setUASName(const QString& name)
{
    this->name = name;
1737
    writeSettings();
1738
    emit nameChanged(name);
1739
    emit systemSpecsChanged(uasId);
1740 1741
}

1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753 1754
/**
 * Sets an action
 *
 **/
void UAS::setAction(MAV_ACTION action)
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, action);
    // Send message twice to increase chance that it reaches its goal
    sendMessage(msg);
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1755
/**
lm's avatar
lm committed
1756
 * Launches the system
pixhawk's avatar
pixhawk committed
1757 1758 1759 1760
 *
 **/
void UAS::launch()
{
1761
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1762
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1763
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_TAKEOFF);
1764 1765 1766
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1767 1768 1769 1770 1771 1772 1773 1774
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1775
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1776
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1777
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1778 1779 1780
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1781 1782 1783 1784 1785 1786 1787 1788
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1789
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1790
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1791
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1792 1793 1794
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808
}

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;

1809 1810 1811 1812 1813 1814
    if(mode == (int)MAV_MODE_MANUAL)
    {
        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
1815

1816 1817 1818 1819 1820 1821
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
    }
    else
    {
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
1822 1823
}

1824 1825 1826 1827 1828
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1829 1830 1831 1832 1833
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1834

pixhawk's avatar
pixhawk committed
1835 1836
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1837

pixhawk's avatar
pixhawk committed
1838 1839 1840 1841 1842
        break;
    default:

        break;
    }
1843
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1844 1845 1846

}

1847

1848
/*void UAS::requestWaypoints()
1849 1850 1851 1852 1853
{
//    mavlink_message_t msg;
//    mavlink_msg_waypoint_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 25);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1854 1855
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1856 1857
}

pixhawk's avatar
pixhawk committed
1858 1859
void UAS::setWaypoint(Waypoint* wp)
{
1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877
//    mavlink_message_t msg;
//    mavlink_waypoint_set_t set;
//    set.id = wp->id;
//    //QString name = wp->name;
//    // FIXME Check if this works properly
//    //name.truncate(MAVLINK_MSG_WAYPOINT_SET_FIELD_NAME_LEN);
//    //strcpy((char*)set.name, name.toStdString().c_str());
//    set.autocontinue = wp->autocontinue;
//    set.target_component = 25; // FIXME
//    set.target_system = uasId;
//    set.active = wp->current;
//    set.x = wp->x;
//    set.y = wp->y;
//    set.z = wp->z;
//    set.yaw = wp->yaw;
//    mavlink_msg_waypoint_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &set);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1878 1879 1880 1881
}

void UAS::setWaypointActive(int id)
{
1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904
//    mavlink_message_t msg;
//    mavlink_waypoint_set_active_t active;
//    active.id = id;
//    active.target_system = uasId;
//    active.target_component = 25; // FIXME
//    mavlink_msg_waypoint_set_active_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &active);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
//    // TODO This should be not directly emitted, but rather being fed back from the UAS
//    emit waypointSelected(getUASID(), id);
}

void UAS::clearWaypointList()
{
//    mavlink_message_t msg;
//    // FIXME
//    mavlink_waypoint_clear_list_t clist;
//    clist.target_system = uasId;
//    clist.target_component = 25;  // FIXME
//    mavlink_msg_waypoint_clear_list_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &clist);
//    sendMessage(msg);
//    qDebug() << "UAS clears Waypoints!";
1905
}*/
pixhawk's avatar
pixhawk committed
1906 1907 1908 1909


void UAS::halt()
{
1910
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1911
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1912
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1913 1914 1915
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1916 1917 1918 1919
}

void UAS::go()
{
1920
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1921
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1922
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1923 1924 1925
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1926 1927 1928 1929 1930
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1931
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1932
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1933
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1934 1935 1936
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1937 1938 1939 1940 1941 1942 1943 1944
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1945
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1946
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1947
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1948 1949 1950
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962 1963 1964 1965 1966 1967 1968 1969 1970 1971 1972 1973 1974 1975
}

/**
 * All systems are immediately shut down (e.g. the main power line is cut).
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
    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)
    {
1976
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1977
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1978
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1979 1980 1981
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1982 1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996 1997 1998 1999 2000 2001 2002 2003 2004
        result = true;
    }
    return result;
}

void UAS::shutdown()
{
    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
2005
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2006
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
2007
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
2008 2009 2010
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
2011 2012 2013 2014
        result = true;
    }
}

2015 2016
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2017 2018 2019 2020 2021 2022
    mavlink_message_t msg;
    mavlink_msg_position_target_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, x, y, z, yaw);

    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
2023 2024
}

pixhawk's avatar
pixhawk committed
2025 2026 2027
/**
 * @return The name of this system as string in human-readable form
 */
2028
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2029 2030 2031 2032 2033 2034 2035 2036 2037 2038 2039 2040 2041 2042 2043 2044 2045 2046
{
    QString result;
    if (name == "")
    {
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
    }
    else
    {
        result = name;
    }
    return result;
}

void UAS::addLink(LinkInterface* link)
{
    if (!links->contains(link))
    {
        links->append(link);
2047
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2048 2049 2050
    }
}

2051 2052 2053 2054 2055 2056 2057 2058 2059
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
    if (link)
    {
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2060 2061 2062 2063 2064 2065 2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076
/**
 * @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;
    switch (batteryType)
    {
lm's avatar
lm committed
2077
    case NICD:
pixhawk's avatar
pixhawk committed
2078
        break;
lm's avatar
lm committed
2079
    case NIMH:
pixhawk's avatar
pixhawk committed
2080
        break;
lm's avatar
lm committed
2081
    case LIION:
pixhawk's avatar
pixhawk committed
2082
        break;
lm's avatar
lm committed
2083
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2084 2085 2086
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2087
    case LIFE:
pixhawk's avatar
pixhawk committed
2088
        break;
lm's avatar
lm committed
2089
    case AGZN:
pixhawk's avatar
pixhawk committed
2090 2091 2092 2093
        break;
    }
}

2094 2095
void UAS::setBatterySpecs(const QString& specs)
{
2096
    if (specs.length() == 0 || specs.contains("%"))
2097
    {
2098
        batteryRemainingEstimateEnabled = false;
2099
        bool ok;
2100 2101 2102
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2103 2104 2105 2106 2107 2108 2109 2110
        if (ok)
        {
            warnLevelPercent = temp;
        }
        else
        {
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2111 2112 2113 2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132
    }
    else
    {
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
        if (parts.length() == 3)
        {
            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;
        }
2133 2134 2135 2136
        else
        {
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2137 2138 2139 2140 2141
    }
}

QString UAS::getBatterySpecs()
{
2142 2143 2144 2145 2146 2147 2148 2149
    if (batteryRemainingEstimateEnabled)
    {
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
    }
    else
    {
        return QString("%1%").arg(warnLevelPercent);
    }
2150 2151
}

pixhawk's avatar
pixhawk committed
2152 2153 2154 2155 2156 2157 2158 2159 2160 2161 2162 2163 2164
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
2165 2166 2167
/**
 * @return charge level in percent - 0 - 100
 */
2168
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2169
{
2170
    if (batteryRemainingEstimateEnabled)
2171
    {
2172 2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183
        if (lpVoltage < emptyVoltage)
        {
            chargeLevel = 0.0f;
        }
        else if (lpVoltage > fullVoltage)
        {
            chargeLevel = 100.0f;
        }
        else
        {
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2184 2185
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2186 2187
}

lm's avatar
lm committed
2188 2189 2190 2191
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
2192
        GAudioOutput::instance()->alert(tr("SYSTEM %1 HAS LOW BATTERY").arg(getUASName()));
2193
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2194 2195 2196 2197 2198 2199 2200 2201 2202 2203 2204 2205
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
    if (lowBattAlarm)
    {
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}