UAS.cc 91.7 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
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),
LM's avatar
LM committed
77 78 79
paramManager(NULL),
attitudeStamped(true),
lastAttitude(0)
pixhawk's avatar
pixhawk committed
80
{
81
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
82
    setBattery(LIPOLY, 3);
83
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
84
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
85
    statusTimeout->start(500);
86
    readSettings();
pixhawk's avatar
pixhawk committed
87 88 89 90
}

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

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

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

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

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

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

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

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

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

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

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

LM's avatar
LM committed
192 193 194 195
    // Only accept messages from this system (condition 1)
    // and only then if a) attitudeStamped is disabled OR b) attitudeStamped is enabled
    // and we already got one attitude packet
    if (message.sysid == uasId && (!attitudeStamped || (attitudeStamped && (lastAttitude != 0)) || message.msgid == MAVLINK_MSG_ID_ATTITUDE))
196
    {
pixhawk's avatar
pixhawk committed
197 198
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
199

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

228 229 230 231 232
            break;
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
            // Receive named value message
            receiveMessageNamedValue(message);
pixhawk's avatar
pixhawk committed
233 234 235 236 237 238
            break;
        case MAVLINK_MSG_ID_BOOT:
            getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);
            emit statusChanged(this, uasState, stateDescription);
            onboardTimeOffset = 0; // Reset offset measurement
            break;
239 240
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
LM's avatar
LM committed
241 242 243 244 245 246 247 248 249 250 251 252
                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;

253 254
                if (state.status != this->status)
                {
LM's avatar
LM committed
255 256 257 258 259 260
                    statechanged = true;
                    this->status = state.status;
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
                    emit statusChanged(this->status);

261 262
                    shortStateText = uasState;

LM's avatar
LM committed
263 264
                    stateAudio = " changed status to " + uasState;
                }
265

266 267
                if (navMode != state.nav_mode)
                {
LM's avatar
LM committed
268 269 270
                    emit navModeChanged(uasId, state.nav_mode, getNavModeText(state.nav_mode));
                    navMode = state.nav_mode;
                }
lm's avatar
lm committed
271

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

275 276
                if (this->mode != static_cast<int>(state.mode))
                {
LM's avatar
LM committed
277 278 279
                    modechanged = true;
                    this->mode = static_cast<int>(state.mode);
                    QString mode;
280

LM's avatar
LM committed
281 282 283 284 285 286 287
                    switch (state.mode) {
                    case (uint8_t)MAV_MODE_LOCKED:
                        mode = "LOCKED MODE";
                        break;
                    case (uint8_t)MAV_MODE_MANUAL:
                        mode = "MANUAL MODE";
                        break;
288

289
#ifdef MAVLINK_ENABLED_SLUGS
LM's avatar
LM committed
290 291 292 293 294 295 296 297 298 299 300 301 302
                    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;
303
#else
LM's avatar
LM committed
304 305 306 307 308 309 310 311 312 313 314 315 316
                    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;
317
#endif
LM's avatar
LM committed
318 319 320
                    case (uint8_t)MAV_MODE_READY:
                        mode = "READY MODE";
                        break;
321

LM's avatar
LM committed
322 323 324
                    case (uint8_t)MAV_MODE_TEST3:
                        mode = "TEST3 MODE";
                        break;
325

LM's avatar
LM committed
326 327 328 329 330 331 332
                    case (uint8_t)MAV_MODE_RC_TRAINING:
                        mode = "RC TRAINING MODE";
                        break;
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }
lm's avatar
lm committed
333

334 335
                    shortModeText = mode;

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

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

LM's avatar
LM committed
340 341 342 343 344 345
                    modeAudio = " is now in " + mode;
                }
                currentVoltage = state.vbat/1000.0f;
                lpVoltage = filterVoltage(currentVoltage);
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
346 347
                if (!batteryRemainingEstimateEnabled)
                {
LM's avatar
LM committed
348 349 350 351 352
                    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);
353

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

LM's avatar
LM committed
364 365
                // COMMUNICATIONS DROP RATE
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
366 367


LM's avatar
LM committed
368 369
                //add for development
                //emit remoteControlRSSIChanged(state.packet_drop/1000.0f);
lm's avatar
lm committed
370

LM's avatar
LM committed
371 372 373
                //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
374

James Goppert's avatar
James Goppert committed
375

LM's avatar
LM committed
376 377 378
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;

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

399 400
                if (state.status == MAV_STATE_POWEROFF)
                {
LM's avatar
LM committed
401 402 403
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
404
            }
LM's avatar
LM committed
405
            break;
406 407

#ifdef MAVLINK_ENABLED_PIXHAWK
408 409
        case MAVLINK_MSG_ID_CONTROL_STATUS:
            {
LM's avatar
LM committed
410 411 412 413 414 415 416 417 418 419 420 421 422 423
                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
424
#endif // PIXHAWK
425 426
        case MAVLINK_MSG_ID_RAW_IMU:
            {
LM's avatar
LM committed
427 428 429 430 431 432 433 434 435 436 437 438 439 440 441
                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;
442 443
        case MAVLINK_MSG_ID_SCALED_IMU:
            {
LM's avatar
LM committed
444 445 446 447 448 449 450 451 452 453
                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);
454 455 456
                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
457 458
            }
            break;
pixhawk's avatar
pixhawk committed
459 460
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
461
            //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
462 463 464
            {
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
LM's avatar
LM committed
465 466
                quint64 time = getUnixReferenceTime(attitude.usec);
                lastAttitude = time;
LM's avatar
LM committed
467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484
                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
485

LM's avatar
LM committed
486
                attitudeKnown = true;
lm's avatar
lm committed
487

LM's avatar
LM committed
488 489 490 491 492 493
                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);
494

495
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
496
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
497
            }
LM's avatar
LM committed
498
            break;
499 500
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
501 502 503 504 505 506 507 508 509 510 511 512
                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);

513 514
                if (!attitudeKnown)
                {
LM's avatar
LM committed
515 516 517
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
518

LM's avatar
LM committed
519 520 521 522 523 524
                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;
525 526
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
            {
LM's avatar
LM committed
527 528 529 530 531 532 533 534 535 536 537 538 539 540
                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;
541
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
542
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
543
            //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
544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569
            {
                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
570
            }
LM's avatar
LM committed
571
            break;
572
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
573 574
            //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
575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599
            {
                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);
600
            }
LM's avatar
LM committed
601
            break;
602 603
        case MAVLINK_MSG_ID_GLOBAL_POSITION:
            {
LM's avatar
LM committed
604 605 606
                mavlink_global_position_t pos;
                mavlink_msg_global_position_decode(&message, &pos);
                quint64 time = getUnixTime();
607 608 609
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
LM's avatar
LM committed
610 611 612 613 614 615 616 617 618 619 620 621 622 623
                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();
624
                }
LM's avatar
LM committed
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 661 662 663 664 665 666
                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));
                    }
667 668
                }
            }
LM's avatar
LM committed
669
            break;
670 671
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
LM's avatar
LM committed
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 700 701 702 703 704 705
                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
706 707
                }
            }
LM's avatar
LM committed
708
            break;
709 710
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
LM's avatar
LM committed
711 712
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
713 714
                for(int i = 0; i < (int)pos.satellites_visible; i++)
                {
LM's avatar
LM committed
715 716
                    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]));
                }
717
            }
LM's avatar
LM committed
718
            break;
719 720
        case MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET:
            {
LM's avatar
LM committed
721 722
                mavlink_gps_local_origin_set_t pos;
                mavlink_msg_gps_local_origin_set_decode(&message, &pos);
LM's avatar
LM committed
723
                emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
LM's avatar
LM committed
724 725
            }
            break;
726 727
        case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
LM's avatar
LM committed
728 729 730 731 732 733 734 735 736
                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;
737

738 739
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
            {
LM's avatar
LM committed
740 741 742 743 744 745 746 747
                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;
748

749 750
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            {
LM's avatar
LM committed
751 752 753 754 755 756 757 758 759 760 761
                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);
762 763 764 765 766 767 768 769 770
                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
771 772
            }
            break;
773 774
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
LM's avatar
LM committed
775 776 777 778 779 780 781 782 783 784 785
                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
786
            }
LM's avatar
LM committed
787
            break;
788 789
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
LM's avatar
LM committed
790 791 792 793 794 795 796 797
                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
798 799
                if (!parameters.contains(component))
                {
LM's avatar
LM committed
800 801
                    parameters.insert(component, new QMap<QString, float>());
                }
802

LM's avatar
LM committed
803 804 805
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
                parameters.value(component)->insert(parameterName, val);
806

LM's avatar
LM committed
807 808 809 810 811
                // 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
812 813 814
        case MAVLINK_MSG_ID_ACTION_ACK:
            mavlink_action_ack_t ack;
            mavlink_msg_action_ack_decode(&message, &ack);
815 816
            if (ack.result == 1)
            {
lm's avatar
lm committed
817
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed action: %1").arg(ack.action));
818 819 820
            }
            else
            {
lm's avatar
lm committed
821
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected action: %1").arg(ack.action));
822 823
            }
            break;
pixhawk's avatar
pixhawk committed
824
        case MAVLINK_MSG_ID_DEBUG:
825
            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
826
            break;
LM's avatar
LM committed
827
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
828
            {
LM's avatar
LM committed
829 830 831 832 833 834 835 836
                mavlink_roll_pitch_yaw_thrust_setpoint_t out;
                mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
                quint64 time = getUnixTime(out.time_ms*1000);
                emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
                emit valueChanged(uasId, "att control roll", "rad", out.roll, time);
                emit valueChanged(uasId, "att control pitch", "rad", out.pitch, time);
                emit valueChanged(uasId, "att control yaw", "rad", out.yaw, time);
                emit valueChanged(uasId, "att control thrust", "0-1", out.thrust, time);
LM's avatar
LM committed
837 838
            }
            break;
839 840
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
LM's avatar
LM committed
841 842
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
843 844
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
845 846
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
847
            }
LM's avatar
LM committed
848
            break;
pixhawk's avatar
pixhawk committed
849

850 851
        case MAVLINK_MSG_ID_WAYPOINT:
            {
LM's avatar
LM committed
852 853 854
                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;
855 856
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
857 858
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
859
            }
LM's avatar
LM committed
860
            break;
pixhawk's avatar
pixhawk committed
861

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

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

884 885
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
            {
LM's avatar
LM committed
886 887 888 889 890 891 892 893
                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
894

895 896
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
            {
LM's avatar
LM committed
897 898 899 900 901
                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
902

903 904
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
905 906 907 908 909
                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;
910 911
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
            {
LM's avatar
LM committed
912 913 914 915 916 917 918 919 920 921 922 923 924
                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;
925 926
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
927 928 929 930 931 932 933 934 935 936 937
                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;
938
#ifdef MAVLINK_ENABLED_PIXHAWK
939 940
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
941 942 943 944 945 946 947 948 949 950 951
                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;
952

953 954
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
955 956 957 958 959 960 961 962 963 964 965
                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;
966 967
                }

968 969
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
970 971 972 973 974
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
975

LM's avatar
LM committed
976
                ++imagePacketsArrived;
977

LM's avatar
LM committed
978 979 980 981 982 983 984 985
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    imagePacketsArrived = 0;
                    emit imageReady(this);
                    qDebug() << "imageReady emitted. all packets arrived";
                }
986
            }
LM's avatar
LM committed
987
            break;
988
#endif
989
        case MAVLINK_MSG_ID_DEBUG_VECT:
990 991 992 993 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
        {
            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
1065
#ifdef MAVLINK_ENABLED_UALBERTA
1066 1067
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
LM's avatar
LM committed
1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078
                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;
1079 1080
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
LM's avatar
LM committed
1081 1082
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
1083 1084 1085 1086 1087 1088
                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
1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107

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

1109
#endif
LM's avatar
LM committed
1110
            // Messages to ignore
1111
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
1112
            break;
1113 1114 1115 1116
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
1117 1118 1119 1120 1121 1122 1123
                    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
1124
            }
LM's avatar
LM committed
1125
            break;
pixhawk's avatar
pixhawk committed
1126 1127 1128 1129
        }
    }
}

1130 1131 1132 1133 1134 1135 1136 1137 1138
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;
1139
    qDebug() << "lat:" << home.latitude << " lon:" << home.longitude;
1140 1141 1142 1143 1144
    mavlink_message_t msg;
    mavlink_msg_gps_set_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
    sendMessage(msg);
}

1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159
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()));


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

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

void UAS::startRadioControlCalibration()
{
1204 1205 1206
    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
1207 1208
}

lm's avatar
lm committed
1209 1210
void UAS::startDataRecording()
{
1211 1212 1213
    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
1214 1215 1216 1217
}

void UAS::pauseDataRecording()
{
1218 1219 1220
    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
1221 1222 1223 1224
}

void UAS::stopDataRecording()
{
1225 1226 1227
    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
1228 1229
}

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

LM's avatar
LM committed
1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303
quint64 UAS::getUnixReferenceTime(quint64 time)
{
    // Same as getUnixTime, but does not react to attitudeStamped mode
    if (time == 0)
    {
        //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
        return QGC::groundTimeMilliseconds();
    }
    // Check if time is smaller than 40 years,
    // assuming no system without Unix timestamp
    // runs longer than 40 years continuously without
    // reboot. In worst case this will add/subtract the
    // communication delay between GCS and MAV,
    // it will never alter the timestamp in a safety
    // critical way.
    //
    // Calculation:
    // 40 years
    // 365 days
    // 24 hours
    // 60 minutes
    // 60 seconds
    // 1000 milliseconds
    // 1000 microseconds
#ifndef _MSC_VER
    else if (time < 1261440000000000LLU)
#else
        else if (time < 1261440000000000)
#endif
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
        if (onboardTimeOffset == 0)
        {
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
        }
        return time/1000 + onboardTimeOffset;
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
        return time/1000;
    }
}

/**
 * @warning If attitudeStamped is enabled, this function will not actually return the precise time stamp
 *          of this measurement augmented to UNIX time, but will MOVE the timestamp IN TIME to match
 *          the last measured attitude. There is no reason why one would want this, except for
 *          system setups where the onboard clock is not present or broken and datasets should
 *          be collected that are still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED
 *          RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
 */
1304 1305
quint64 UAS::getUnixTime(quint64 time)
{
LM's avatar
LM committed
1306 1307 1308 1309
    if (attitudeStamped)
    {
        return lastAttitude;
    }
1310 1311
    if (time == 0)
    {
LM's avatar
LM committed
1312
        //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
LM's avatar
LM committed
1313
        return QGC::groundTimeMilliseconds();
1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330
    }
    // 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
1331
#ifndef _MSC_VER
1332
    else if (time < 1261440000000000LLU)
1333
#else
LM's avatar
LM committed
1334
        else if (time < 1261440000000000)
1335
#endif
LM's avatar
LM committed
1336 1337
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1338 1339
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1340
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1341
        }
1342
        return time/1000 + onboardTimeOffset;
1343 1344 1345
    }
    else
    {
1346 1347
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1348
        return time/1000;
1349 1350 1351
    }
}

1352 1353
QList<QString> UAS::getParameterNames(int component)
{
1354 1355
    if (parameters.contains(component))
    {
1356
        return parameters.value(component)->keys();
1357 1358 1359
    }
    else
    {
1360 1361 1362 1363 1364 1365 1366 1367 1368
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1369
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1370
{
1371 1372
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
    {
1373
        //this->mode = mode; //no call assignament, update receive message from UAS
pixhawk's avatar
pixhawk committed
1374
        mavlink_message_t msg;
lm's avatar
lm committed
1375
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
1376
        sendMessage(msg);
lm's avatar
lm committed
1377
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
1378 1379 1380
    }
    else
    {
1381 1382
        qDebug() << "uas Mode not assign: " << mode;
    }
pixhawk's avatar
pixhawk committed
1383 1384 1385 1386 1387
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1388 1389 1390 1391
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1392
            sendMessage(link, message);
1393 1394 1395
        }
        else
        {
1396 1397 1398
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1399 1400 1401
    }
}

1402 1403 1404 1405
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1406

1407 1408 1409 1410
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1411
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1412 1413 1414 1415 1416 1417
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1418
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1419 1420
                        sendMessage(serial, message);
                    }
1421 1422 1423 1424 1425 1426
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1427 1428
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1429
    if(!link) return;
pixhawk's avatar
pixhawk committed
1430 1431 1432
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1433
    int len = mavlink_msg_to_send_buffer(buffer, &message);
1434
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
1435
    // If link is connected
1436 1437
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1438 1439 1440 1441 1442 1443 1444 1445
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1446
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1447
{
1448
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1449 1450
}

1451 1452
QString UAS::getNavModeText(int mode)
{
1453 1454
    switch (mode)
    {
1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486
    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
1487 1488
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1489 1490
    switch (statusCode)
    {
lm's avatar
lm committed
1491
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1492
        uasState = tr("UNINIT");
1493
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1494
        break;
lm's avatar
lm committed
1495
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1496
        uasState = tr("BOOT");
1497
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1498
        break;
lm's avatar
lm committed
1499
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1500
        uasState = tr("CALIBRATING");
1501
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1502
        break;
lm's avatar
lm committed
1503
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1504
        uasState = tr("ACTIVE");
1505
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1506
        break;
lm's avatar
lm committed
1507 1508
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1509
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1510 1511
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1512
        uasState = tr("CRITICAL");
1513
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1514
        break;
lm's avatar
lm committed
1515
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1516
        uasState = tr("EMERGENCY");
1517
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1518
        break;
James Goppert's avatar
James Goppert committed
1519
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1520 1521 1522
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1523

lm's avatar
lm committed
1524
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1525
        uasState = tr("SHUTDOWN");
1526
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1527
        break;
1528

lm's avatar
lm committed
1529
    default:
pixhawk's avatar
pixhawk committed
1530
        uasState = tr("UNKNOWN");
1531
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1532 1533 1534 1535
        break;
    }
}

1536 1537
QImage UAS::getImage()
{
LM's avatar
LM committed
1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584
#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!";
        }
    }
1585 1586
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1587
    //imageRecBuffer.clear();
1588
    return image;
1589 1590
#else
	return QImage();
LM's avatar
LM committed
1591
#endif
1592

1593 1594 1595 1596
}

void UAS::requestImage()
{
1597
#ifdef MAVLINK_ENABLED_PIXHAWK
1598 1599
    qDebug() << "trying to get an image from the uas...";

1600 1601 1602
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1603 1604 1605 1606
        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);
    }
1607
#endif
1608
}
pixhawk's avatar
pixhawk committed
1609 1610 1611 1612 1613 1614 1615 1616 1617


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1618
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1619
{
1620 1621
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1622
        return 0;
1623 1624 1625
    }
    else
    {
pixhawk's avatar
pixhawk committed
1626 1627 1628 1629
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1630
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1631 1632 1633 1634
{
    return commStatus;
}

1635 1636 1637
void UAS::requestParameters()
{
    mavlink_message_t msg;
1638
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1639 1640
    // Send message twice to increase chance of reception
    sendMessage(msg);
1641 1642
}

1643
void UAS::writeParametersToStorage()
1644
{
1645 1646 1647
    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
1648
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1649 1650 1651 1652 1653 1654 1655 1656 1657
    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
1658 1659
}

1660
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1661 1662
{
    // Buffers to write data to
1663
    mavlink_message_t msg;
1664
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1665 1666
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1667
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1668 1669
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1670 1671
    // 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
1672 1673
    stream.req_message_rate = 0;
    // Start / stop the message
1674
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1675 1676 1677 1678 1679
    // 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
1680
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1681 1682
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1683 1684 1685
    sendMessage(msg);
}

1686
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1687 1688 1689
{
    // Buffers to write data to
    mavlink_message_t msg;
1690
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1691
    // Select the message to request from now on
1692
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1693
    // Select the update rate in Hz the message should be send
1694
    stream.req_message_rate = rate;
lm's avatar
lm committed
1695
    // Start / stop the message
1696
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1697 1698 1699 1700 1701
    // 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
1702
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1703 1704
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1705 1706 1707
    sendMessage(msg);
}

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

1730
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1731
{
1732 1733 1734 1735 1736
#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
1737 1738 1739
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1740
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1741
    // Select the update rate in Hz the message should be send
1742
    stream.req_message_rate = rate;
1743
    // Start / stop the message
1744
    stream.start_stop = (rate) ? 1 : 0;
1745 1746 1747 1748 1749 1750
    // 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);
1751 1752
    // Send message twice to increase chance of reception
    sendMessage(msg);
1753
    sendMessage(msg);
1754
#endif
lm's avatar
lm committed
1755 1756
}

1757
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1758
{
1759 1760 1761 1762
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1763
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1764
    // Select the update rate in Hz the message should be send
1765
    stream.req_message_rate = rate;
1766
    // Start / stop the message
1767
    stream.start_stop = (rate) ? 1 : 0;
1768 1769 1770 1771 1772 1773
    // 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);
1774 1775
    // Send message twice to increase chance of reception
    sendMessage(msg);
1776
    sendMessage(msg);
lm's avatar
lm committed
1777 1778
}

lm's avatar
lm committed
1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799
//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);
//}
1800

1801
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1802 1803 1804 1805 1806
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1807
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1808
    // Select the update rate in Hz the message should be send
1809
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1810
    // Start / stop the message
1811
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822
    // 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);
}

1823
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1824 1825 1826 1827 1828
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1829
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1830
    // Select the update rate in Hz the message should be send
1831
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1832
    // Start / stop the message
1833
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844
    // 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);
}

1845
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1846 1847 1848 1849 1850
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1851
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1852
    // Select the update rate in Hz the message should be send
1853
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1854
    // Start / stop the message
1855
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866
    // 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);
}

1867
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1868 1869 1870 1871 1872
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1873
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1874
    // Select the update rate in Hz the message should be send
1875
    stream.req_message_rate = rate;
1876
    // Start / stop the message
1877
    stream.start_stop = (rate) ? 1 : 0;
1878 1879 1880 1881 1882 1883
    // 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);
1884 1885
    // Send message twice to increase chance of reception
    sendMessage(msg);
1886
    sendMessage(msg);
1887 1888
}

lm's avatar
lm committed
1889 1890 1891 1892 1893 1894 1895
/**
 * 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
1896 1897
void UAS::setParameter(const int component, const QString& id, const float value)
{
1898 1899
    if (!id.isNull())
    {
1900 1901 1902 1903 1904 1905 1906
        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
1907 1908
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1909
            // String characters
1910 1911
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1912 1913
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1914 1915 1916 1917 1918
            //        // 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';
            //        }
1919
            // Zero fill
1920 1921
            else
            {
1922 1923
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1924
        }
1925 1926
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1927
    }
1928 1929
}

1930 1931 1932 1933 1934 1935 1936 1937 1938 1939 1940 1941
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;
}

1942 1943 1944 1945
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
1946 1947 1948 1949
    if (airframe == 0)
    {
        switch (systemType)
        {
1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960
        case MAV_FIXED_WING:
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
        case MAV_QUADROTOR:
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1961 1962 1963
void UAS::setUASName(const QString& name)
{
    this->name = name;
1964
    writeSettings();
1965
    emit nameChanged(name);
1966
    emit systemSpecsChanged(uasId);
1967 1968
}

lm's avatar
lm committed
1969 1970 1971 1972
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
    mavlink_command_t cmd;
1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996 1997
    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
1998 1999 2000
    sendMessage(msg);
}

2001 2002 2003 2004 2005 2006 2007 2008 2009 2010 2011 2012 2013
/**
 * 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
2014
/**
lm's avatar
lm committed
2015
 * Launches the system
pixhawk's avatar
pixhawk committed
2016 2017 2018 2019
 *
 **/
void UAS::launch()
{
2020
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2021
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2022
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_TAKEOFF);
2023 2024 2025
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2026 2027 2028 2029 2030 2031 2032 2033
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
2034
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2035
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2036
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
2037 2038 2039
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2040 2041 2042 2043 2044 2045 2046 2047
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
2048
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2049
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2050
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
2051 2052 2053
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2054 2055 2056 2057 2058 2059 2060 2061 2062 2063 2064 2065 2066 2067
}

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;

2068 2069
    if(mode == (int)MAV_MODE_MANUAL)
    {
2070 2071 2072 2073
        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
2074

2075
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
2076 2077 2078
    }
    else
    {
2079 2080
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2081 2082
}

2083 2084 2085 2086 2087
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2088 2089
void UAS::receiveButton(int buttonIndex)
{
2090 2091
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2092
    case 0:
pixhawk's avatar
pixhawk committed
2093

pixhawk's avatar
pixhawk committed
2094 2095
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2096

pixhawk's avatar
pixhawk committed
2097 2098 2099 2100 2101
        break;
    default:

        break;
    }
2102
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2103 2104 2105

}

2106

2107
/*void UAS::requestWaypoints()
2108 2109 2110 2111 2112
{
//    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
2113 2114
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
2115 2116
}

pixhawk's avatar
pixhawk committed
2117 2118
void UAS::setWaypoint(Waypoint* wp)
{
2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134 2135 2136
//    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
2137 2138 2139 2140
}

void UAS::setWaypointActive(int id)
{
2141 2142 2143 2144 2145 2146 2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157 2158 2159 2160 2161 2162 2163
//    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!";
2164
}*/
pixhawk's avatar
pixhawk committed
2165 2166 2167 2168


void UAS::halt()
{
2169
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2170
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2171
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
2172 2173 2174
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2175 2176 2177 2178
}

void UAS::go()
{
2179
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2180
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2181
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
2182 2183 2184
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2185 2186 2187 2188 2189
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
2190
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2191
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2192
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
2193 2194 2195
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2196 2197 2198 2199 2200 2201 2202 2203
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2204
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2205
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2206
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
2207 2208 2209
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2210 2211 2212 2213 2214 2215 2216 2217 2218 2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230 2231 2232
}

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


2233 2234
    if (ret == QMessageBox::Yes)
    {
2235
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2236
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
2237
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
2238 2239 2240
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
2241 2242 2243 2244 2245
        result = true;
    }
    return result;
}

2246 2247
void UAS::startHil()
{
James Goppert's avatar
James Goppert committed
2248 2249 2250 2251 2252 2253
    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);
2254 2255
}

2256 2257
void UAS::stopHil()
{
James Goppert's avatar
James Goppert committed
2258 2259 2260 2261 2262 2263
    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);
2264 2265 2266
}


pixhawk's avatar
pixhawk committed
2267 2268 2269 2270 2271 2272 2273
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?");
2274

pixhawk's avatar
pixhawk committed
2275 2276 2277 2278 2279 2280 2281
    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()));

2282 2283
    if (ret == QMessageBox::Yes)
    {
pixhawk's avatar
pixhawk committed
2284
        // If the active UAS is set, execute command
2285
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2286
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
2287
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
2288 2289 2290
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
2291

pixhawk's avatar
pixhawk committed
2292 2293 2294 2295
        result = true;
    }
}

2296 2297
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2298 2299 2300 2301 2302 2303
    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);
2304 2305
}

pixhawk's avatar
pixhawk committed
2306 2307 2308
/**
 * @return The name of this system as string in human-readable form
 */
2309
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2310 2311
{
    QString result;
2312 2313
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2314
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2315 2316 2317
    }
    else
    {
pixhawk's avatar
pixhawk committed
2318 2319 2320 2321 2322
        result = name;
    }
    return result;
}

2323 2324 2325 2326 2327 2328 2329 2330 2331 2332
const QString& UAS::getShortState() const
{
    return shortStateText;
}

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

pixhawk's avatar
pixhawk committed
2333 2334
void UAS::addLink(LinkInterface* link)
{
2335 2336
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2337
        links->append(link);
2338
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2339 2340 2341
    }
}

2342 2343 2344
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2345 2346
    if (link)
    {
2347 2348 2349 2350
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2351 2352 2353 2354 2355 2356 2357 2358 2359 2360 2361 2362 2363 2364 2365
/**
 * @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;
2366 2367
    switch (batteryType)
    {
lm's avatar
lm committed
2368
    case NICD:
pixhawk's avatar
pixhawk committed
2369
        break;
lm's avatar
lm committed
2370
    case NIMH:
pixhawk's avatar
pixhawk committed
2371
        break;
lm's avatar
lm committed
2372
    case LIION:
pixhawk's avatar
pixhawk committed
2373
        break;
lm's avatar
lm committed
2374
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2375 2376 2377
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2378
    case LIFE:
pixhawk's avatar
pixhawk committed
2379
        break;
lm's avatar
lm committed
2380
    case AGZN:
pixhawk's avatar
pixhawk committed
2381 2382 2383 2384
        break;
    }
}

2385 2386
void UAS::setBatterySpecs(const QString& specs)
{
2387 2388
    if (specs.length() == 0 || specs.contains("%"))
    {
2389
        batteryRemainingEstimateEnabled = false;
2390
        bool ok;
2391 2392 2393
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2394 2395
        if (ok)
        {
2396
            warnLevelPercent = temp;
2397 2398 2399
        }
        else
        {
2400 2401
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2402 2403 2404
    }
    else
    {
2405 2406 2407 2408 2409
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2410 2411
        if (parts.length() == 3)
        {
2412 2413 2414 2415 2416 2417 2418 2419 2420 2421 2422
            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;
2423 2424 2425
        }
        else
        {
2426 2427
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2428 2429 2430 2431 2432
    }
}

QString UAS::getBatterySpecs()
{
2433 2434
    if (batteryRemainingEstimateEnabled)
    {
2435
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2436 2437 2438
    }
    else
    {
2439 2440
        return QString("%1%").arg(warnLevelPercent);
    }
2441 2442
}

pixhawk's avatar
pixhawk committed
2443 2444 2445 2446 2447 2448 2449 2450 2451 2452 2453 2454 2455
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
2456 2457 2458
/**
 * @return charge level in percent - 0 - 100
 */
2459
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2460
{
2461 2462 2463 2464
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2465
            chargeLevel = 0.0f;
2466 2467 2468
        }
        else if (lpVoltage > fullVoltage)
        {
2469
            chargeLevel = 100.0f;
2470 2471 2472
        }
        else
        {
2473 2474
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2475 2476
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2477 2478
}

lm's avatar
lm committed
2479 2480
void UAS::startLowBattAlarm()
{
2481 2482
    if (!lowBattAlarm)
    {
2483
        GAudioOutput::instance()->alert(tr("SYSTEM %1 HAS LOW BATTERY").arg(getUASName()));
2484
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2485 2486 2487 2488 2489 2490
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2491 2492
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2493 2494 2495 2496
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}