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

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

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

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

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
144 145
void UAS::setSelected()
{
146
    if (UASManager::instance()->getActiveUAS() != this) {
147 148 149 150 151 152 153 154
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

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

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

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

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

190 191
    if (message.sysid == uasId)
    {
pixhawk's avatar
pixhawk committed
192 193
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
194

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

223 224 225 226 227
            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
228 229 230 231 232 233
            break;
        case MAVLINK_MSG_ID_BOOT:
            getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);
            emit statusChanged(this, uasState, stateDescription);
            onboardTimeOffset = 0; // Reset offset measurement
            break;
234 235
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
LM's avatar
LM committed
236 237 238 239 240 241 242 243 244 245 246 247
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);

                // FIXME
                //qDebug() << "1 SYSTEM STATUS:" << state.status;

                QString audiostring = "System " + getUASName();
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;

248 249
                if (state.status != this->status)
                {
LM's avatar
LM committed
250 251 252 253 254 255
                    statechanged = true;
                    this->status = state.status;
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
                    emit statusChanged(this->status);

256 257
                    shortStateText = uasState;

LM's avatar
LM committed
258 259
                    stateAudio = " changed status to " + uasState;
                }
260

261 262
                if (navMode != state.nav_mode)
                {
LM's avatar
LM committed
263 264 265
                    emit navModeChanged(uasId, state.nav_mode, getNavModeText(state.nav_mode));
                    navMode = state.nav_mode;
                }
lm's avatar
lm committed
266

LM's avatar
LM committed
267 268
                emit loadChanged(this,state.load/10.0f);
                emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime());
pixhawk's avatar
pixhawk committed
269

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

LM's avatar
LM committed
276 277 278 279 280 281 282
                    switch (state.mode) {
                    case (uint8_t)MAV_MODE_LOCKED:
                        mode = "LOCKED MODE";
                        break;
                    case (uint8_t)MAV_MODE_MANUAL:
                        mode = "MANUAL MODE";
                        break;
283

284
#ifdef MAVLINK_ENABLED_SLUGS
LM's avatar
LM committed
285 286 287 288 289 290 291 292 293 294 295 296 297
                    case (uint8_t)MAV_MODE_AUTO:
                        mode = "WAYPOINT MODE";
                        break;
                    case (uint8_t)MAV_MODE_GUIDED:
                        mode = "MID-L CMDS MODE";
                        break;

                    case (uint8_t)MAV_MODE_TEST1:
                        mode = "PASST MODE";
                        break;
                    case (uint8_t)MAV_MODE_TEST2:
                        mode = "SEL PT MODE";
                        break;
298
#else
LM's avatar
LM committed
299 300 301 302 303 304 305 306 307 308 309 310 311
                    case (uint8_t)MAV_MODE_AUTO:
                        mode = "AUTO MODE";
                        break;
                    case (uint8_t)MAV_MODE_GUIDED:
                        mode = "GUIDED MODE";
                        break;

                    case (uint8_t)MAV_MODE_TEST1:
                        mode = "TEST1 MODE";
                        break;
                    case (uint8_t)MAV_MODE_TEST2:
                        mode = "TEST2 MODE";
                        break;
312
#endif
LM's avatar
LM committed
313 314 315
                    case (uint8_t)MAV_MODE_READY:
                        mode = "READY MODE";
                        break;
316

LM's avatar
LM committed
317 318 319
                    case (uint8_t)MAV_MODE_TEST3:
                        mode = "TEST3 MODE";
                        break;
320

LM's avatar
LM committed
321 322 323 324 325 326 327
                    case (uint8_t)MAV_MODE_RC_TRAINING:
                        mode = "RC TRAINING MODE";
                        break;
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }
lm's avatar
lm committed
328

329 330
                    shortModeText = mode;

LM's avatar
LM committed
331
                    emit modeChanged(this->getUASID(), mode, "");
332

LM's avatar
LM committed
333
                    //qDebug() << "2 SYSTEM MODE:" << mode;
334

LM's avatar
LM committed
335 336 337 338 339 340
                    modeAudio = " is now in " + mode;
                }
                currentVoltage = state.vbat/1000.0f;
                lpVoltage = filterVoltage(currentVoltage);
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
341 342
                if (!batteryRemainingEstimateEnabled)
                {
LM's avatar
LM committed
343 344 345 346 347
                    chargeLevel = state.battery_remaining/10.0f;
                }
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
348

LM's avatar
LM committed
349
                // LOW BATTERY ALARM
350 351
                if (lpVoltage < warnVoltage)
                {
LM's avatar
LM committed
352
                    startLowBattAlarm();
353 354 355
                }
                else
                {
LM's avatar
LM committed
356 357
                    stopLowBattAlarm();
                }
358

LM's avatar
LM committed
359 360
                // COMMUNICATIONS DROP RATE
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
361 362


LM's avatar
LM committed
363 364
                //add for development
                //emit remoteControlRSSIChanged(state.packet_drop/1000.0f);
lm's avatar
lm committed
365

LM's avatar
LM committed
366 367 368
                //float en = state.packet_drop/1000.0f;
                //emit remoteControlChannelRawChanged(0, en);//MAVLINK_MSG_ID_RC_CHANNELS_RAW
                //emit remoteControlChannelScaledChanged(0, en/100.0f);//MAVLINK_MSG_ID_RC_CHANNELS_SCALED
369

James Goppert's avatar
James Goppert committed
370

LM's avatar
LM committed
371 372 373
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;

                // AUDIO
374 375
                if (modechanged && statechanged)
                {
LM's avatar
LM committed
376 377
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
378 379 380
                }
                else
                {
LM's avatar
LM committed
381 382 383
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
384 385
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
                {
LM's avatar
LM committed
386
                    GAudioOutput::instance()->startEmergency();
387 388 389
                }
                else if (modechanged || statechanged)
                {
LM's avatar
LM committed
390 391 392 393
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }

394 395
                if (state.status == MAV_STATE_POWEROFF)
                {
LM's avatar
LM committed
396 397 398
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
399
            }
LM's avatar
LM committed
400
            break;
401 402

#ifdef MAVLINK_ENABLED_PIXHAWK
403 404
        case MAVLINK_MSG_ID_CONTROL_STATUS:
            {
LM's avatar
LM committed
405 406 407 408 409 410 411 412 413 414 415 416 417 418
                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
419
#endif // PIXHAWK
420 421
        case MAVLINK_MSG_ID_RAW_IMU:
            {
LM's avatar
LM committed
422 423 424 425 426 427 428 429 430 431 432 433 434 435 436
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
                quint64 time = getUnixTime(raw.usec);

                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);
                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);
                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);
            }
            break;
437 438
        case MAVLINK_MSG_ID_SCALED_IMU:
            {
LM's avatar
LM committed
439 440 441 442 443 444 445 446 447 448
                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);
449 450 451
                emit valueChanged(uasId, "mag x", "uTesla", scaled.xmag/100.0f, time);
                emit valueChanged(uasId, "mag y", "uTesla", scaled.ymag/100.0f, time);
                emit valueChanged(uasId, "mag z", "uTesla", scaled.zmag/100.0f, time);
LM's avatar
LM committed
452 453
            }
            break;
pixhawk's avatar
pixhawk committed
454 455
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
456
            //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
457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478
            {
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
                quint64 time = getUnixTime(attitude.usec);
                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);
                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);

                // Emit in angles

                // Convert yaw angle to compass value
                // in 0 - 360 deg range
                float compass = (yaw/M_PI)*180.0+360.0f;
                while (compass > 360.0f) {
                    compass -= 360.0f;
                }
lm's avatar
lm committed
479

LM's avatar
LM committed
480
                attitudeKnown = true;
lm's avatar
lm committed
481

LM's avatar
LM committed
482 483 484 485 486 487
                emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time);
                emit valueChanged(uasId, "heading deg", "deg", compass, time);
                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);
488

489
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
490
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
491
            }
LM's avatar
LM committed
492
            break;
493 494
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
495 496 497 498 499 500 501 502 503 504 505 506
                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);
                emit valueChanged(uasId, "throttle", "%", hud.throttle, time);
                emit thrustChanged(this, hud.throttle/100.0);

507 508
                if (!attitudeKnown)
                {
LM's avatar
LM committed
509 510 511
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
512

LM's avatar
LM committed
513 514 515 516 517 518
                emit altitudeChanged(uasId, hud.alt);
                //yaw = (hud.heading-180.0f/360.0f)*M_PI;
                //emit attitudeChanged(this, roll, pitch, yaw, getUnixTime());
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, getUnixTime());
            }
            break;
519 520
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
            {
LM's avatar
LM committed
521 522 523 524 525 526 527 528 529 530 531 532 533 534
                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);
                emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time);
            }
            break;
535
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
536
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
537
            //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
538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563
            {
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
                quint64 time = getUnixTime(pos.usec);
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
                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);
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);

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

                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
564
            }
LM's avatar
LM committed
565
            break;
566
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
567 568
            //std::cerr << std::endl;
            //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
LM's avatar
LM committed
569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593
            {
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
                quint64 time = getUnixTime();
                latitude = pos.lat/(double)1E7;
                longitude = pos.lon/(double)1E7;
                altitude = pos.alt/1000.0;
                speedX = pos.vx/100.0;
                speedY = pos.vy/100.0;
                speedZ = pos.vz/100.0;
                emit valueChanged(uasId, "latitude", "deg", latitude, time);
                emit valueChanged(uasId, "longitude", "deg", longitude, time);
                emit valueChanged(uasId, "altitude", "m", altitude, time);
                double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
                emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
                emit globalPositionChanged(this, latitude, longitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
594
            }
LM's avatar
LM committed
595
            break;
596 597
        case MAVLINK_MSG_ID_GLOBAL_POSITION:
            {
LM's avatar
LM committed
598 599 600
                mavlink_global_position_t pos;
                mavlink_msg_global_position_decode(&message, &pos);
                quint64 time = getUnixTime();
601 602 603
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
LM's avatar
LM committed
604 605 606 607 608 609 610 611 612 613 614 615 616 617
                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);
                double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
                emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
                emit globalPositionChanged(this, latitude, longitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
618
                }
LM's avatar
LM committed
619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660
                positionLock = true;
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
            }
            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);

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

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

                if (pos.fix_type > 0) {
                    emit valueChanged(uasId, "gps speed", "m/s", pos.v, time);
                    latitude = pos.lat;
                    longitude = pos.lon;
                    altitude = pos.alt;
                    positionLock = true;

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt) {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
                    emit valueChanged(uasId, "altitude", "m", pos.alt, 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));
                    }
661 662
                }
            }
LM's avatar
LM committed
663
            break;
664 665
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
LM's avatar
LM committed
666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699
                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);
                    latitude = pos.lat/(double)1E7;
                    longitude = pos.lon/(double)1E7;
                    altitude = pos.alt/1000.0;
                    positionLock = true;

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt) {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
                    emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, 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));
                    }
lm's avatar
lm committed
700 701
                }
            }
LM's avatar
LM committed
702
            break;
703 704
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
LM's avatar
LM committed
705 706
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
707 708
                for(int i = 0; i < (int)pos.satellites_visible; i++)
                {
LM's avatar
LM committed
709 710
                    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]));
                }
711
            }
LM's avatar
LM committed
712
            break;
713 714
        case MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET:
            {
LM's avatar
LM committed
715 716
                mavlink_gps_local_origin_set_t pos;
                mavlink_msg_gps_local_origin_set_decode(&message, &pos);
LM's avatar
LM committed
717
                emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
LM's avatar
LM committed
718 719
            }
            break;
720 721
        case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
LM's avatar
LM committed
722 723 724 725 726 727 728 729 730
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
                quint64 time = this->getUnixTime(pressure.usec);
                emit valueChanged(uasId, "abs pressure", "raw", pressure.press_abs, time);
                emit valueChanged(uasId, "diff pressure 1", "raw", pressure.press_diff1, time);
                emit valueChanged(uasId, "diff pressure 2", "raw", pressure.press_diff2, time);
                emit valueChanged(uasId, "temperature", "raw", pressure.temperature, time);
            }
            break;
731

732 733
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
            {
LM's avatar
LM committed
734 735 736 737 738 739 740 741
                mavlink_scaled_pressure_t pressure;
                mavlink_msg_scaled_pressure_decode(&message, &pressure);
                quint64 time = this->getUnixTime(pressure.usec);
                emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
                emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time);
                emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time);
            }
            break;
742

743 744
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            {
LM's avatar
LM committed
745 746 747 748 749 750 751 752 753 754 755
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
                emit remoteControlChannelRawChanged(0, channels.chan1_raw);
                emit remoteControlChannelRawChanged(1, channels.chan2_raw);
                emit remoteControlChannelRawChanged(2, channels.chan3_raw);
                emit remoteControlChannelRawChanged(3, channels.chan4_raw);
                emit remoteControlChannelRawChanged(4, channels.chan5_raw);
                emit remoteControlChannelRawChanged(5, channels.chan6_raw);
                emit remoteControlChannelRawChanged(6, channels.chan7_raw);
                emit remoteControlChannelRawChanged(7, channels.chan8_raw);
756 757 758 759 760 761 762 763 764
                quint64 time = getUnixTime();
                emit valueChanged(uasId, "rc in #1", "us", channels.chan1_raw, time);
                emit valueChanged(uasId, "rc in #2", "us", channels.chan2_raw, time);
                emit valueChanged(uasId, "rc in #3", "us", channels.chan3_raw, time);
                emit valueChanged(uasId, "rc in #4", "us", channels.chan4_raw, time);
                emit valueChanged(uasId, "rc in #5", "us", channels.chan5_raw, time);
                emit valueChanged(uasId, "rc in #6", "us", channels.chan6_raw, time);
                emit valueChanged(uasId, "rc in #7", "us", channels.chan7_raw, time);
                emit valueChanged(uasId, "rc in #8", "us", channels.chan8_raw, time);
LM's avatar
LM committed
765 766
            }
            break;
767 768
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
LM's avatar
LM committed
769 770 771 772 773 774 775 776 777 778 779
                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
780
            }
LM's avatar
LM committed
781
            break;
782 783
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
LM's avatar
LM committed
784 785 786 787 788 789 790 791
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
                QByteArray bytes((char*)value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
                QString parameterName = QString(bytes);
                int component = message.compid;
                float val = value.param_value;

                // Insert component if necessary
792 793
                if (!parameters.contains(component))
                {
LM's avatar
LM committed
794 795
                    parameters.insert(component, new QMap<QString, float>());
                }
796

LM's avatar
LM committed
797 798 799
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
                parameters.value(component)->insert(parameterName, val);
800

LM's avatar
LM committed
801 802 803 804 805
                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, val);
                emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val);
            }
            break;
lm's avatar
lm committed
806 807 808
        case MAVLINK_MSG_ID_ACTION_ACK:
            mavlink_action_ack_t ack;
            mavlink_msg_action_ack_decode(&message, &ack);
809 810
            if (ack.result == 1)
            {
lm's avatar
lm committed
811
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed action: %1").arg(ack.action));
812 813 814
            }
            else
            {
lm's avatar
lm committed
815
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected action: %1").arg(ack.action));
816 817
            }
            break;
pixhawk's avatar
pixhawk committed
818
        case MAVLINK_MSG_ID_DEBUG:
819
            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
820
            break;
821 822
        case MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT:
            {
LM's avatar
LM committed
823 824 825 826 827 828 829 830 831
                mavlink_attitude_controller_output_t out;
                mavlink_msg_attitude_controller_output_decode(&message, &out);
                quint64 time = MG::TIME::getGroundTimeNowUsecs();
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
                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);
            }
            break;
832 833
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
LM's avatar
LM committed
834 835 836 837 838 839 840 841 842
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
                quint64 time = MG::TIME::getGroundTimeNow();
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
                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);
            }
            break;
843 844
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
LM's avatar
LM committed
845 846
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
847 848
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
849 850
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
851
            }
LM's avatar
LM committed
852
            break;
pixhawk's avatar
pixhawk committed
853

854 855
        case MAVLINK_MSG_ID_WAYPOINT:
            {
LM's avatar
LM committed
856 857 858
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
859 860
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
861 862
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
863
            }
LM's avatar
LM committed
864
            break;
pixhawk's avatar
pixhawk committed
865

866 867
        case MAVLINK_MSG_ID_WAYPOINT_ACK:
            {
LM's avatar
LM committed
868 869
                mavlink_waypoint_ack_t wpa;
                mavlink_msg_waypoint_ack_decode(&message, &wpa);
870 871
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
872 873
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
874
            }
LM's avatar
LM committed
875
            break;
876

877 878
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
LM's avatar
LM committed
879 880
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
881 882
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
883 884
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
885
            }
LM's avatar
LM committed
886
            break;
pixhawk's avatar
pixhawk committed
887

888 889
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
            {
LM's avatar
LM committed
890 891 892 893 894 895 896 897
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
                QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq);
                GAudioOutput::instance()->say(text);
                emit textMessageReceived(message.sysid, message.compid, 0, text);
            }
            break;
pixhawk's avatar
pixhawk committed
898

899 900
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
            {
LM's avatar
LM committed
901 902 903 904 905
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
906

907 908
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
909 910 911 912 913
                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;
914 915
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
            {
LM's avatar
LM committed
916 917 918 919 920 921 922 923 924 925 926 927 928
                mavlink_servo_output_raw_t servos;
                mavlink_msg_servo_output_raw_decode(&message, &servos);
                quint64 time = getUnixTime();
                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;
929 930
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
931 932 933 934 935 936 937 938 939 940 941
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
                //b.append('\0');
                QString text = QString(b);
                int severity = mavlink_msg_statustext_get_severity(&message);
                //qDebug() << "RECEIVED STATUS:" << text;false
                //emit statusTextReceived(severity, text);
                emit textMessageReceived(uasId, message.compid, severity, text);
            }
            break;
942
#ifdef MAVLINK_ENABLED_PIXHAWK
943 944
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
945 946 947 948 949 950 951 952 953 954 955
                qDebug() << "RECIEVED ACK TO GET IMAGE";
                mavlink_data_transmission_handshake_t p;
                mavlink_msg_data_transmission_handshake_decode(&message, &p);
                imageSize = p.size;
                imagePackets = p.packets;
                imagePayload = p.payload;
                imageQuality = p.jpg_quality;
                imageType = p.type;
                imageStart = QGC::groundTimeMilliseconds();
            }
            break;
956

957 958
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
959 960 961 962 963 964 965 966 967 968 969
                mavlink_encapsulated_data_t img;
                mavlink_msg_encapsulated_data_decode(&message, &img);
                int seq = img.seqnr;
                int pos = seq * imagePayload;

                // Check if we have a valid transaction
                if (imagePackets == 0)
                {
                    // NO VALID TRANSACTION - ABORT
                    // Restart statemachine
                    imagePacketsArrived = 0;
970 971
                }

972 973
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
974 975 976 977 978
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
979

LM's avatar
LM committed
980
                ++imagePacketsArrived;
981

LM's avatar
LM committed
982 983 984 985 986 987 988 989
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    imagePacketsArrived = 0;
                    emit imageReady(this);
                    qDebug() << "imageReady emitted. all packets arrived";
                }
990
            }
LM's avatar
LM committed
991
            break;
992
#endif
993
        case MAVLINK_MSG_ID_DEBUG_VECT:
994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 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 1065 1066 1067 1068
        {
            mavlink_debug_vect_t vect;
            mavlink_msg_debug_vect_decode(&message, &vect);
            QString str((const char*)vect.name);
            quint64 time = getUnixTime(vect.usec);
            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);
        }
        break;
        // WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET
//        case MAVLINK_MSG_ID_MEMORY_VECT:
//        {
//            mavlink_memory_vect_t vect;
//            mavlink_msg_memory_vect_decode(&message, &vect);
//            QString str("mem_%1");
//            quint64 time = getUnixTime(0);
//            int16_t *mem0 = (int16_t *)&vect.value[0];
//            uint16_t *mem1 = (uint16_t *)&vect.value[0];
//            int32_t *mem2 = (int32_t *)&vect.value[0];
//            // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem
//            float *mem4 = (float *)&vect.value[0];
//            if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ;
//            if ( vect.ver == 1)
//            {
//                switch (vect.type) {
//                default:
//                case 0:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
//                    break;
//                case 1:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
//                    break;
//                case 2:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
//                    break;
//                case 3:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
//                    break;
//                case 4:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
//                    break;
//                case 5:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
//                    break;
//                case 6:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
//                    break;
//                }
//            }
//        }
//        break;
				//#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
1069
#ifdef MAVLINK_ENABLED_UALBERTA
1070 1071
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
LM's avatar
LM committed
1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = getUnixTime();
                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);
            }
            break;
1083 1084
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
LM's avatar
LM committed
1085 1086
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
1087 1088 1089 1090 1091 1092
                QVector<uint16_t> aileron;
                QVector<uint16_t> elevator;
                QVector<uint16_t> rudder;
                QVector<uint16_t> gyro;
                QVector<uint16_t> pitch;
                QVector<uint16_t> throttle;
LM's avatar
LM committed
1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111

                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN; ++i)
                    aileron << radioMsg.aileron[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN; ++i)
                    elevator << radioMsg.elevator[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN; ++i)
                    rudder << radioMsg.rudder[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN; ++i)
                    gyro << radioMsg.gyro[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN; ++i)
                    pitch << radioMsg.pitch[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN; ++i)
                    throttle << radioMsg.throttle[i];

                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;
1112

1113
#endif
LM's avatar
LM committed
1114
            // Messages to ignore
1115
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
1116
            break;
1117 1118 1119 1120
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
1121 1122 1123 1124 1125 1126 1127
                    unknownPackets.append(message.msgid);
                    QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid);
                    GAudioOutput::instance()->say(errString+tr(", please check console for details."));
                    emit textMessageReceived(uasId, message.compid, 255, errString);
                    std::cout << "Unable to decode message from system " << std::dec << static_cast<int>(message.sysid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
                    //qDebug() << std::cerr << "Unable to decode message from system " << std::dec << static_cast<int>(message.acid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
                }
lm's avatar
lm committed
1128
            }
LM's avatar
LM committed
1129
            break;
pixhawk's avatar
pixhawk committed
1130 1131 1132 1133
        }
    }
}

1134 1135 1136 1137 1138 1139 1140 1141 1142
void UAS::setHomePosition(double lat, double lon, double alt)
{
    // Send new home position to UAS
    mavlink_gps_set_global_origin_t home;
    home.target_system = uasId;
    home.target_component = 0; // ALL components
    home.latitude = lat*1E7;
    home.longitude = lon*1E7;
    home.altitude = alt*1000;
1143
    qDebug() << "lat:" << home.latitude << " lon:" << home.longitude;
1144 1145 1146 1147 1148
    mavlink_message_t msg;
    mavlink_msg_gps_set_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
    sendMessage(msg);
}

1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163
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()));


1164 1165
    if (ret == QMessageBox::Yes)
    {
1166
        mavlink_message_t msg;
1167
        mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_ACTION_SET_ORIGIN);
1168 1169 1170 1171 1172 1173 1174 1175 1176 1177
        // 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
1178 1179
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1180
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1181
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1182 1183
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
1184
#else
lm's avatar
lm committed
1185 1186 1187 1188
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1189
#endif
pixhawk's avatar
pixhawk committed
1190 1191
}

pixhawk's avatar
pixhawk committed
1192 1193
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1194
#ifdef MAVLINK_ENABLED_PIXHAWK
1195 1196 1197
    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
1198
#else
1199 1200 1201 1202
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1203 1204 1205 1206 1207
#endif
}

void UAS::startRadioControlCalibration()
{
1208 1209 1210
    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
1211 1212
}

lm's avatar
lm committed
1213 1214
void UAS::startDataRecording()
{
1215 1216 1217
    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
1218 1219 1220 1221
}

void UAS::pauseDataRecording()
{
1222 1223 1224
    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
1225 1226 1227 1228
}

void UAS::stopDataRecording()
{
1229 1230 1231
    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
1232 1233
}

pixhawk's avatar
pixhawk committed
1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254
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);
}

1255 1256
quint64 UAS::getUnixTime(quint64 time)
{
1257 1258
    if (time == 0)
    {
LM's avatar
LM committed
1259
        //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
LM's avatar
LM committed
1260
        return QGC::groundTimeMilliseconds();
1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277
    }
    // 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
1278
#ifndef _MSC_VER
1279
    else if (time < 1261440000000000LLU)
1280
#else
LM's avatar
LM committed
1281
        else if (time < 1261440000000000)
1282
#endif
LM's avatar
LM committed
1283 1284
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1285 1286
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1287
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1288
        }
1289
        return time/1000 + onboardTimeOffset;
1290 1291 1292
    }
    else
    {
1293 1294
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1295
        return time/1000;
1296 1297 1298
    }
}

1299 1300
QList<QString> UAS::getParameterNames(int component)
{
1301 1302
    if (parameters.contains(component))
    {
1303
        return parameters.value(component)->keys();
1304 1305 1306
    }
    else
    {
1307 1308 1309 1310 1311 1312 1313 1314 1315
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1316
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1317
{
1318 1319
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
    {
1320
        //this->mode = mode; //no call assignament, update receive message from UAS
pixhawk's avatar
pixhawk committed
1321
        mavlink_message_t msg;
lm's avatar
lm committed
1322
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
1323
        sendMessage(msg);
lm's avatar
lm committed
1324
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
1325 1326 1327
    }
    else
    {
1328 1329
        qDebug() << "uas Mode not assign: " << mode;
    }
pixhawk's avatar
pixhawk committed
1330 1331 1332 1333 1334
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1335 1336 1337 1338
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1339
            sendMessage(link, message);
1340 1341 1342
        }
        else
        {
1343 1344 1345
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1346 1347 1348
    }
}

1349 1350 1351 1352
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1353

1354 1355 1356 1357
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1358
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1359 1360 1361 1362 1363 1364
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1365
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1366 1367
                        sendMessage(serial, message);
                    }
1368 1369 1370 1371 1372 1373
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1374 1375
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1376
    if(!link) return;
pixhawk's avatar
pixhawk committed
1377 1378 1379
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1380
    int len = mavlink_msg_to_send_buffer(buffer, &message);
1381
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
1382
    // If link is connected
1383 1384
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1385 1386 1387 1388 1389 1390 1391 1392
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1393
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1394
{
1395
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1396 1397
}

1398 1399
QString UAS::getNavModeText(int mode)
{
1400 1401
    switch (mode)
    {
1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433
    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
1434 1435
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1436 1437
    switch (statusCode)
    {
lm's avatar
lm committed
1438
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1439
        uasState = tr("UNINIT");
1440
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1441
        break;
lm's avatar
lm committed
1442
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1443
        uasState = tr("BOOT");
1444
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1445
        break;
lm's avatar
lm committed
1446
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1447
        uasState = tr("CALIBRATING");
1448
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1449
        break;
lm's avatar
lm committed
1450
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1451
        uasState = tr("ACTIVE");
1452
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1453
        break;
lm's avatar
lm committed
1454 1455
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1456
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1457 1458
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1459
        uasState = tr("CRITICAL");
1460
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1461
        break;
lm's avatar
lm committed
1462
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1463
        uasState = tr("EMERGENCY");
1464
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1465
        break;
James Goppert's avatar
James Goppert committed
1466
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1467 1468 1469
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1470

lm's avatar
lm committed
1471
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1472
        uasState = tr("SHUTDOWN");
1473
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1474
        break;
1475

lm's avatar
lm committed
1476
    default:
pixhawk's avatar
pixhawk committed
1477
        uasState = tr("UNKNOWN");
1478
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1479 1480 1481 1482
        break;
    }
}

1483 1484
QImage UAS::getImage()
{
LM's avatar
LM committed
1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531
#ifdef MAVLINK_ENABLED_PIXHAWK

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

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

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

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

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

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

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

    }
    // BMP with header
    else if (imageType == MAVLINK_DATA_STREAM_IMG_BMP ||
             imageType == MAVLINK_DATA_STREAM_IMG_JPEG ||
             imageType == MAVLINK_DATA_STREAM_IMG_PGM ||
             imageType == MAVLINK_DATA_STREAM_IMG_PNG)
    {
       if (!image.loadFromData(imageRecBuffer))
        {
           qDebug() << "Loading data from image buffer failed!";
        }
    }
1532 1533
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1534
    //imageRecBuffer.clear();
1535
    return image;
1536 1537
#else
	return QImage();
LM's avatar
LM committed
1538
#endif
1539

1540 1541 1542 1543
}

void UAS::requestImage()
{
1544
#ifdef MAVLINK_ENABLED_PIXHAWK
1545 1546
    qDebug() << "trying to get an image from the uas...";

1547 1548 1549
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1550 1551 1552 1553
        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);
    }
1554
#endif
1555
}
pixhawk's avatar
pixhawk committed
1556 1557 1558 1559 1560 1561 1562 1563 1564


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1565
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1566
{
1567 1568
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1569
        return 0;
1570 1571 1572
    }
    else
    {
pixhawk's avatar
pixhawk committed
1573 1574 1575 1576
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1577
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1578 1579 1580 1581
{
    return commStatus;
}

1582 1583 1584
void UAS::requestParameters()
{
    mavlink_message_t msg;
1585
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1586 1587
    // Send message twice to increase chance of reception
    sendMessage(msg);
1588 1589
}

1590
void UAS::writeParametersToStorage()
1591
{
1592 1593 1594
    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
1595
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1596 1597 1598 1599 1600 1601 1602 1603 1604
    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
1605 1606
}

1607
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1608 1609
{
    // Buffers to write data to
1610
    mavlink_message_t msg;
1611
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1612 1613
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1614
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1615 1616
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1617 1618
    // 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
1619 1620
    stream.req_message_rate = 0;
    // Start / stop the message
1621
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1622 1623 1624 1625 1626
    // 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
1627
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1628 1629
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1630 1631 1632
    sendMessage(msg);
}

1633
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1634 1635 1636
{
    // Buffers to write data to
    mavlink_message_t msg;
1637
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1638
    // Select the message to request from now on
1639
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1640
    // Select the update rate in Hz the message should be send
1641
    stream.req_message_rate = rate;
lm's avatar
lm committed
1642
    // Start / stop the message
1643
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1644 1645 1646 1647 1648
    // 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
1649
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1650 1651
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1652 1653 1654
    sendMessage(msg);
}

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

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

1704
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1705
{
1706 1707 1708 1709
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1710
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1711
    // Select the update rate in Hz the message should be send
1712
    stream.req_message_rate = rate;
1713
    // Start / stop the message
1714
    stream.start_stop = (rate) ? 1 : 0;
1715 1716 1717 1718 1719 1720
    // 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);
1721 1722
    // Send message twice to increase chance of reception
    sendMessage(msg);
1723
    sendMessage(msg);
lm's avatar
lm committed
1724 1725
}

lm's avatar
lm committed
1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746
//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);
//}
1747

1748
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1749 1750 1751 1752 1753
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1754
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1755
    // Select the update rate in Hz the message should be send
1756
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1757
    // Start / stop the message
1758
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769
    // 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);
}

1770
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1771 1772 1773 1774 1775
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1776
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1777
    // Select the update rate in Hz the message should be send
1778
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1779
    // Start / stop the message
1780
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791
    // 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);
}

1792
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1793 1794 1795 1796 1797
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1798
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1799
    // Select the update rate in Hz the message should be send
1800
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1801
    // Start / stop the message
1802
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813
    // 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);
}

1814
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1815 1816 1817 1818 1819
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1820
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1821
    // Select the update rate in Hz the message should be send
1822
    stream.req_message_rate = rate;
1823
    // Start / stop the message
1824
    stream.start_stop = (rate) ? 1 : 0;
1825 1826 1827 1828 1829 1830
    // 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);
1831 1832
    // Send message twice to increase chance of reception
    sendMessage(msg);
1833
    sendMessage(msg);
1834 1835
}

lm's avatar
lm committed
1836 1837 1838 1839 1840 1841 1842
/**
 * 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
1843 1844
void UAS::setParameter(const int component, const QString& id, const float value)
{
1845 1846
    if (!id.isNull())
    {
1847 1848 1849 1850 1851 1852 1853
        mavlink_message_t msg;
        mavlink_param_set_t p;
        p.param_value = value;
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

        // Copy string into buffer, ensuring not to exceed the buffer size
1854 1855
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1856
            // String characters
1857 1858
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1859 1860
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1861 1862 1863 1864 1865
            //        // 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';
            //        }
1866
            // Zero fill
1867 1868
            else
            {
1869 1870
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1871
        }
1872 1873
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1874
    }
1875 1876
}

1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888
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;
}

1889 1890 1891 1892
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
1893 1894 1895 1896
    if (airframe == 0)
    {
        switch (systemType)
        {
1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907
        case MAV_FIXED_WING:
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
        case MAV_QUADROTOR:
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1908 1909 1910
void UAS::setUASName(const QString& name)
{
    this->name = name;
1911
    writeSettings();
1912
    emit nameChanged(name);
1913
    emit systemSpecsChanged(uasId);
1914 1915
}

lm's avatar
lm committed
1916 1917 1918 1919
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
    mavlink_command_t cmd;
1920 1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939 1940 1941 1942 1943 1944
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
    cmd.target_system = uasId;
    cmd.target_component = 0;
    mavlink_msg_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
    mavlink_command_t cmd;
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
    cmd.target_system = uasId;
    cmd.target_component = component;
    mavlink_msg_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
1945 1946 1947
    sendMessage(msg);
}

1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960
/**
 * 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
1961
/**
lm's avatar
lm committed
1962
 * Launches the system
pixhawk's avatar
pixhawk committed
1963 1964 1965 1966
 *
 **/
void UAS::launch()
{
1967
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1968
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1969
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_TAKEOFF);
1970 1971 1972
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1973 1974 1975 1976 1977 1978 1979 1980
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1981
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1982
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1983
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1984 1985 1986
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1987 1988 1989 1990 1991 1992 1993 1994
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1995
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1996
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1997
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1998 1999 2000
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2001 2002 2003 2004 2005 2006 2007 2008 2009 2010 2011 2012 2013 2014
}

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;

2015 2016
    if(mode == (int)MAV_MODE_MANUAL)
    {
2017 2018 2019 2020
        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
2021

2022
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
2023 2024 2025
    }
    else
    {
2026 2027
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2028 2029
}

2030 2031 2032 2033 2034
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2035 2036
void UAS::receiveButton(int buttonIndex)
{
2037 2038
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2039
    case 0:
pixhawk's avatar
pixhawk committed
2040

pixhawk's avatar
pixhawk committed
2041 2042
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2043

pixhawk's avatar
pixhawk committed
2044 2045 2046 2047 2048
        break;
    default:

        break;
    }
2049
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2050 2051 2052

}

2053

2054
/*void UAS::requestWaypoints()
2055 2056 2057 2058 2059
{
//    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
2060 2061
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
2062 2063
}

pixhawk's avatar
pixhawk committed
2064 2065
void UAS::setWaypoint(Waypoint* wp)
{
2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077 2078 2079 2080 2081 2082 2083
//    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
2084 2085 2086 2087
}

void UAS::setWaypointActive(int id)
{
2088 2089 2090 2091 2092 2093 2094 2095 2096 2097 2098 2099 2100 2101 2102 2103 2104 2105 2106 2107 2108 2109 2110
//    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!";
2111
}*/
pixhawk's avatar
pixhawk committed
2112 2113 2114 2115


void UAS::halt()
{
2116
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2117
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2118
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
2119 2120 2121
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2122 2123 2124 2125
}

void UAS::go()
{
2126
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2127
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2128
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
2129 2130 2131
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2132 2133 2134 2135 2136
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
2137
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2138
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2139
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
2140 2141 2142
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2143 2144 2145 2146 2147 2148 2149 2150
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2151
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2152
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2153
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
2154 2155 2156
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2157 2158 2159 2160 2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179
}

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


2180 2181
    if (ret == QMessageBox::Yes)
    {
2182
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2183
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
2184
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
2185 2186 2187
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
2188 2189 2190 2191 2192
        result = true;
    }
    return result;
}

2193 2194
void UAS::startHil()
{
James Goppert's avatar
James Goppert committed
2195 2196 2197 2198 2199 2200
    mavlink_message_t msg;
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_START_HILSIM);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
2201 2202
}

2203 2204
void UAS::stopHil()
{
James Goppert's avatar
James Goppert committed
2205 2206 2207 2208 2209 2210
    mavlink_message_t msg;
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_STOP_HILSIM);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
2211 2212 2213
}


pixhawk's avatar
pixhawk committed
2214 2215 2216 2217 2218 2219 2220
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?");
2221

pixhawk's avatar
pixhawk committed
2222 2223 2224 2225 2226 2227 2228
    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()));

2229 2230
    if (ret == QMessageBox::Yes)
    {
pixhawk's avatar
pixhawk committed
2231
        // If the active UAS is set, execute command
2232
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2233
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
2234
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
2235 2236 2237
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
2238

pixhawk's avatar
pixhawk committed
2239 2240 2241 2242
        result = true;
    }
}

2243 2244
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2245 2246 2247 2248 2249 2250
    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);
2251 2252
}

pixhawk's avatar
pixhawk committed
2253 2254 2255
/**
 * @return The name of this system as string in human-readable form
 */
2256
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2257 2258
{
    QString result;
2259 2260
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2261
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2262 2263 2264
    }
    else
    {
pixhawk's avatar
pixhawk committed
2265 2266 2267 2268 2269
        result = name;
    }
    return result;
}

2270 2271 2272 2273 2274 2275 2276 2277 2278 2279
const QString& UAS::getShortState() const
{
    return shortStateText;
}

const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2280 2281
void UAS::addLink(LinkInterface* link)
{
2282 2283
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2284
        links->append(link);
2285
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2286 2287 2288
    }
}

2289 2290 2291
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2292 2293
    if (link)
    {
2294 2295 2296 2297
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2298 2299 2300 2301 2302 2303 2304 2305 2306 2307 2308 2309 2310 2311 2312
/**
 * @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;
2313 2314
    switch (batteryType)
    {
lm's avatar
lm committed
2315
    case NICD:
pixhawk's avatar
pixhawk committed
2316
        break;
lm's avatar
lm committed
2317
    case NIMH:
pixhawk's avatar
pixhawk committed
2318
        break;
lm's avatar
lm committed
2319
    case LIION:
pixhawk's avatar
pixhawk committed
2320
        break;
lm's avatar
lm committed
2321
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2322 2323 2324
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2325
    case LIFE:
pixhawk's avatar
pixhawk committed
2326
        break;
lm's avatar
lm committed
2327
    case AGZN:
pixhawk's avatar
pixhawk committed
2328 2329 2330 2331
        break;
    }
}

2332 2333
void UAS::setBatterySpecs(const QString& specs)
{
2334 2335
    if (specs.length() == 0 || specs.contains("%"))
    {
2336
        batteryRemainingEstimateEnabled = false;
2337
        bool ok;
2338 2339 2340
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2341 2342
        if (ok)
        {
2343
            warnLevelPercent = temp;
2344 2345 2346
        }
        else
        {
2347 2348
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2349 2350 2351
    }
    else
    {
2352 2353 2354 2355 2356
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2357 2358
        if (parts.length() == 3)
        {
2359 2360 2361 2362 2363 2364 2365 2366 2367 2368 2369
            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;
2370 2371 2372
        }
        else
        {
2373 2374
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2375 2376 2377 2378 2379
    }
}

QString UAS::getBatterySpecs()
{
2380 2381
    if (batteryRemainingEstimateEnabled)
    {
2382
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2383 2384 2385
    }
    else
    {
2386 2387
        return QString("%1%").arg(warnLevelPercent);
    }
2388 2389
}

pixhawk's avatar
pixhawk committed
2390 2391 2392 2393 2394 2395 2396 2397 2398 2399 2400 2401 2402
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
2403 2404 2405
/**
 * @return charge level in percent - 0 - 100
 */
2406
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2407
{
2408 2409 2410 2411
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2412
            chargeLevel = 0.0f;
2413 2414 2415
        }
        else if (lpVoltage > fullVoltage)
        {
2416
            chargeLevel = 100.0f;
2417 2418 2419
        }
        else
        {
2420 2421
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2422 2423
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2424 2425
}

lm's avatar
lm committed
2426 2427
void UAS::startLowBattAlarm()
{
2428 2429
    if (!lowBattAlarm)
    {
2430
        GAudioOutput::instance()->alert(tr("SYSTEM %1 HAS LOW BATTERY").arg(getUASName()));
2431
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2432 2433 2434 2435 2436 2437
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2438 2439
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2440 2441 2442 2443
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}