UAS.cc 87.4 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 31 32 33
#ifdef QGC_PROTOBUF_ENABLED
#include <google/protobuf/descriptor.h>
#endif

34
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lm's avatar
lm committed
35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77
    uasId(id),
    startTime(QGC::groundTimeMilliseconds()),
    commStatus(COMM_DISCONNECTED),
    name(""),
    autopilot(-1),
    links(new QList<LinkInterface*>()),
    unknownPackets(),
    mavlink(protocol),
    waypointManager(this),
    thrustSum(0),
    thrustMax(10),
    startVoltage(0),
    warnVoltage(9.5f),
    warnLevelPercent(20.0f),
    currentVoltage(12.0f),
    lpVoltage(12.0f),
    batteryRemainingEstimateEnabled(true),
    mode(-1),
    status(-1),
    navMode(-1),
    onboardTimeOffset(0),
    controlRollManual(true),
    controlPitchManual(true),
    controlYawManual(true),
    controlThrustManual(true),
    manualRollAngle(0),
    manualPitchAngle(0),
    manualYawAngle(0),
    manualThrust(0),
    receiveDropRate(0),
    sendDropRate(0),
    lowBattAlarm(false),
    positionLock(false),
    localX(0.0),
    localY(0.0),
    localZ(0.0),
    latitude(0.0),
    longitude(0.0),
    altitude(0.0),
    roll(0.0),
    pitch(0.0),
    yaw(0.0),
    statusTimeout(new QTimer(this)),
LM's avatar
LM committed
78
    #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
79 80 81 82
    receivedPointCloudTimestamp(0.0),
    receivedRGBDImageTimestamp(0.0),
    receivedObstacleListTimestamp(0.0),
    receivedPathTimestamp(0.0),
LM's avatar
LM committed
83
    #endif
lm's avatar
lm committed
84 85 86 87 88 89 90 91 92 93
    paramsOnceRequested(false),
    airframe(QGC_AIRFRAME_EASYSTAR),
    attitudeKnown(false),
    paramManager(NULL),
    attitudeStamped(false),
    lastAttitude(0),
    simulation(new QGCFlightGearLink(this)),
    isLocalPositionKnown(false),
    isGlobalPositionKnown(false),
    systemIsArmed(false)
pixhawk's avatar
pixhawk committed
94
{
95 96 97 98 99 100
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
    }

101
    color = UASInterface::getNextColor();
lm's avatar
lm committed
102
    setBatterySpecs(QString("9V,9.5V,12.6V"));
103
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
104
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
105
    statusTimeout->start(500);
106
    readSettings();
107 108 109 110

    // Initial signals
    emit disarmed();
    emit armingChanged(false);
pixhawk's avatar
pixhawk committed
111 112 113 114
}

UAS::~UAS()
{
115
    writeSettings();
pixhawk's avatar
pixhawk committed
116
    delete links;
117
    links=NULL;
pixhawk's avatar
pixhawk committed
118 119
}

120 121 122 123 124
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
125 126
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
127
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
128 129 130 131 132 133 134 135 136
    settings.endGroup();
    settings.sync();
}

void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
137 138
    this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
    this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
139
    if (settings.contains("BATTERY_SPECS")) {
140 141
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
142 143 144
    settings.endGroup();
}

145
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
146 147 148 149
{
    return uasId;
}

150 151
void UAS::updateState()
{
152 153
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
154 155
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
156 157 158 159
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

160 161
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
162 163
    if (positionLock)
    {
164
        positionLock = false;
165 166 167
    }
    else
    {
lm's avatar
lm committed
168
        if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock)
169
        {
170 171 172 173 174
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
175 176
void UAS::setSelected()
{
177 178
    if (UASManager::instance()->getActiveUAS() != this)
    {
179 180 181 182 183 184 185 186
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

bool UAS::getSelected() const
{
    return (UASManager::instance()->getActiveUAS() == this);
pixhawk's avatar
pixhawk committed
187 188 189 190
}

void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
191
    if (!link) return;
192 193
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
194
        addLink(link);
195
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
196 197
    }

LM's avatar
LM committed
198 199 200 201 202 203 204
    if (!components.contains(message.compid))
    {
        QString componentName;

        switch (message.compid)
        {
        case MAV_COMP_ID_ALL:
LM's avatar
LM committed
205 206 207 208
        {
            componentName = "ANONYMOUS";
            break;
        }
LM's avatar
LM committed
209
        case MAV_COMP_ID_IMU:
LM's avatar
LM committed
210 211 212 213
        {
            componentName = "IMU #1";
            break;
        }
LM's avatar
LM committed
214
        case MAV_COMP_ID_CAMERA:
LM's avatar
LM committed
215 216 217 218
        {
            componentName = "CAMERA";
            break;
        }
LM's avatar
LM committed
219
        case MAV_COMP_ID_MISSIONPLANNER:
LM's avatar
LM committed
220 221 222 223
        {
            componentName = "MISSIONPLANNER";
            break;
        }
LM's avatar
LM committed
224 225 226 227 228 229
        }

        components.insert(message.compid, componentName);
        emit componentCreated(uasId, message.compid, componentName);
    }

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

LM's avatar
LM committed
232 233 234 235
    // 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))
236
    {
pixhawk's avatar
pixhawk committed
237 238
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
239

240 241 242
        bool multiComponentSourceDetected = false;
        bool wrongComponent = false;

243 244 245 246 247 248 249 250 251 252 253
        switch (message.compid)
        {
        case MAV_COMP_ID_IMU_2:
            // Prefer IMU 2 over IMU 1 (FIXME)
            componentID[message.msgid] = MAV_COMP_ID_IMU_2;
            break;
        default:
            // Do nothing
            break;
        }

254 255 256
        // Store component ID
        if (componentID[message.msgid] == -1)
        {
257
            // Prefer the first component
258 259 260 261 262 263 264 265 266 267 268 269 270 271 272
            componentID[message.msgid] = message.compid;
        }
        else
        {
            // Got this message already
            if (componentID[message.msgid] != message.compid)
            {
                componentMulti[message.msgid] = true;
                wrongComponent = true;
            }
        }

        if (componentMulti[message.msgid] == true) multiComponentSourceDetected = true;


273 274
        switch (message.msgid)
        {
pixhawk's avatar
pixhawk committed
275
        case MAVLINK_MSG_ID_HEARTBEAT:
276
        {
LM's avatar
LM committed
277 278 279 280
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
281
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
282
            emit heartbeat(this);
283 284
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
285 286 287 288 289
			
			// Send the base_mode and system_status values to the plotter. This uses the ground time
			// so the Ground Time checkbox must be ticked for these values to display
            quint64 time = getUnixTime();
			QString name = QString("M%1:HEARTBEAT.%2").arg(message.sysid);
290 291 292
			emit valueChanged(uasId, name.arg("base_mode"), "bits", state.base_mode, time);
			emit valueChanged(uasId, name.arg("custom_mode"), "bits", state.custom_mode, time);
			emit valueChanged(uasId, name.arg("system_status"), "-", state.system_status, time);
293
			
pixhawk's avatar
pixhawk committed
294
            // Set new type if it has changed
295
            if (this->type != state.type)
296
            {
297
                this->type = state.type;
298 299 300 301
                if (airframe == 0)
                {
                    switch (type)
                    {
lm's avatar
lm committed
302
                    case MAV_TYPE_FIXED_WING:
303 304
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
lm's avatar
lm committed
305
                    case MAV_TYPE_QUADROTOR:
306 307
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
308 309 310
                    case MAV_TYPE_HEXAROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
                        break;
311 312 313 314 315
                    default:
                        // Do nothing
                        break;
                    }
                }
316
                this->autopilot = state.autopilot;
pixhawk's avatar
pixhawk committed
317 318
                emit systemTypeSet(this, type);
            }
319

320 321 322 323 324 325 326 327 328 329 330 331 332 333 334
            bool currentlyArmed = state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;

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

336 337 338 339 340 341
            QString audiostring = "System " + getUASName();
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
342 343


344 345 346 347 348 349 350
            if (state.system_status != this->status)
            {
                statechanged = true;
                this->status = state.system_status;
                getStatusForCode((int)state.system_status, uasState, stateDescription);
                emit statusChanged(this, uasState, stateDescription);
                emit statusChanged(this->status);
351

352
                shortStateText = uasState;
353

354 355
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
356

357
            if (this->mode != static_cast<int>(state.base_mode))
358 359
            {
                modechanged = true;
360
                this->mode = static_cast<int>(state.base_mode);
361
                shortModeText = getShortModeTextFor(this->mode);
362

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

365 366
                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed
367

368
            if (navMode != state.custom_mode)
369
            {
370 371
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
372 373
                navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
            }
374

375 376 377 378 379 380 381 382 383 384 385
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
386

387 388 389 390 391 392 393
            if ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY)
            {
                GAudioOutput::instance()->startEmergency();
            }
            else if (modechanged || statechanged)
            {
                GAudioOutput::instance()->stopEmergency();
394
                GAudioOutput::instance()->say(audiostring.toLower());
395
            }
LM's avatar
LM committed
396
        }
397

398 399 400
            break;
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
LM's avatar
LM committed
401 402 403 404 405 406
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_sys_status_t state;
            mavlink_msg_sys_status_decode(&message, &state);
407

408 409 410 411 412 413 414 415 416 417 418 419
			// Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
            quint64 time = getUnixTime();
			QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid);
			emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time);
			emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time);
			emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time);
			emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time);
			emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time);
			emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time);
			emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);

			// Process CPU load.
LM's avatar
LM committed
420
            emit loadChanged(this,state.load/10.0f);
421
			emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
LM's avatar
LM committed
422

423
			// Battery charge/time remaining/voltage calculations
LM's avatar
LM committed
424 425
            currentVoltage = state.voltage_battery/1000.0f;
            lpVoltage = filterVoltage(currentVoltage);
LM's avatar
LM committed
426

LM's avatar
LM committed
427 428 429 430 431 432 433
            if (startVoltage == 0) startVoltage = currentVoltage;
            timeRemaining = calculateTimeRemaining();
            if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
            {
                chargeLevel = state.battery_remaining;
            }
            emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
434 435 436 437 438 439 440 441 442
			emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time);
            emit voltageChanged(message.sysid, currentVoltage);
			emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time);

			// And if the battery current draw is measured, log that also.
			if (state.current_battery != -1)
			{
				emit valueChanged(uasId, name.arg("battery_current"), "A", ((double)state.current_battery) / 100.0f, time);
			}
443

LM's avatar
LM committed
444 445 446 447
            // LOW BATTERY ALARM
            if (lpVoltage < warnVoltage)
            {
                startLowBattAlarm();
448
            }
LM's avatar
LM committed
449
            else
LM's avatar
LM committed
450
            {
LM's avatar
LM committed
451
                stopLowBattAlarm();
pixhawk's avatar
pixhawk committed
452
            }
453

454 455 456 457 458 459
			// Trigger drop rate updates as needed. Here we convert the incoming
			// drop_rate_comm value from 1/100 of a percent in a uint16 to a true
			// percentage as a float. We also cap the incoming value at 100% as defined
			// by the MAVLink specifications.
			if (state.drop_rate_comm > 10000)
			{
460
				state.drop_rate_comm = 10000;
461
			}
462 463
			emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f);
			emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time);
464
		}
LM's avatar
LM committed
465
            break;
pixhawk's avatar
pixhawk committed
466
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499
        {
            if (wrongComponent) break;

            mavlink_attitude_t attitude;
            mavlink_msg_attitude_decode(&message, &attitude);
            quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
            lastAttitude = time;
            roll = QGC::limitAngleToPMPIf(attitude.roll);
            pitch = QGC::limitAngleToPMPIf(attitude.pitch);
            yaw = QGC::limitAngleToPMPIf(attitude.yaw);

            //                // Emit in angles

            //                // Convert yaw angle to compass value
            //                // in 0 - 360 deg range
            //                float compass = (yaw/M_PI)*180.0+360.0f;
            //                if (compass > -10000 && compass < 10000)
            //                {
            //                    while (compass > 360.0f) {
            //                        compass -= 360.0f;
            //                    }
            //                }
            //                else
            //                {
            //                    // Set to 0, since it is an invalid value
            //                    compass = 0.0f;
            //                }

            attitudeKnown = true;
            emit attitudeChanged(this, roll, pitch, yaw, time);
            emit attitudeChanged(this, message.compid, roll, pitch, yaw, time);
            emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
        }
LM's avatar
LM committed
500
            break;
lm's avatar
lm committed
501
        case MAVLINK_MSG_ID_HIL_CONTROLS:
LM's avatar
LM committed
502 503 504 505 506
        {
            mavlink_hil_controls_t hil;
            mavlink_msg_hil_controls_decode(&message, &hil);
            emit hilControlsChanged(hil.time_usec, hil.roll_ailerons, hil.pitch_elevator, hil.yaw_rudder, hil.throttle, hil.mode, hil.nav_mode);
        }
lm's avatar
lm committed
507
            break;
508
        case MAVLINK_MSG_ID_VFR_HUD:
LM's avatar
LM committed
509 510 511 512 513 514
        {
            mavlink_vfr_hud_t hud;
            mavlink_msg_vfr_hud_decode(&message, &hud);
            quint64 time = getUnixTime();
            // Display updated values
            emit thrustChanged(this, hud.throttle/100.0);
lm's avatar
lm committed
515

LM's avatar
LM committed
516 517 518 519
            if (!attitudeKnown)
            {
                yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
520
            }
LM's avatar
LM committed
521 522 523 524

            emit altitudeChanged(uasId, hud.alt);
            emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
        }
LM's avatar
LM committed
525
            break;
lm's avatar
lm committed
526
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
lm's avatar
lm committed
527
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
528
            //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
529 530 531 532
        {
            mavlink_local_position_ned_t pos;
            mavlink_msg_local_position_ned_decode(&message, &pos);
            quint64 time = getUnixTime(pos.time_boot_ms);
LM's avatar
LM committed
533

LM's avatar
LM committed
534 535
            // Emit position always with component ID
            emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time);
536

LM's avatar
LM committed
537 538
            if (!wrongComponent)
            {
539

LM's avatar
LM committed
540 541 542
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
543

LM's avatar
LM committed
544
                // Emit
545

LM's avatar
LM committed
546 547
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
548

LM's avatar
LM committed
549 550 551 552
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
LM's avatar
LM committed
553
                }
LM's avatar
LM committed
554 555
                positionLock = true;
                isLocalPositionKnown = true;
556
            }
LM's avatar
LM committed
557
        }
558 559
            break;
        case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
LM's avatar
LM committed
560 561 562 563 564 565 566
        {
            mavlink_global_vision_position_estimate_t pos;
            mavlink_msg_global_vision_position_estimate_decode(&message, &pos);
            quint64 time = getUnixTime(pos.usec);
            emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time);
            emit attitudeChanged(this, message.compid, pos.roll, pos.pitch, pos.yaw, time);
        }
LM's avatar
LM committed
567
            break;
568
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
569 570
            //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
571 572 573 574 575 576 577 578 579 580 581 582 583 584
        {
            mavlink_global_position_int_t pos;
            mavlink_msg_global_position_int_decode(&message, &pos);
            quint64 time = getUnixTime();
            latitude = pos.lat/(double)1E7;
            longitude = pos.lon/(double)1E7;
            altitude = pos.alt/1000.0;
            speedX = pos.vx/100.0;
            speedY = pos.vy/100.0;
            speedZ = pos.vz/100.0;
            emit globalPositionChanged(this, latitude, longitude, altitude, time);
            emit speedChanged(this, speedX, speedY, speedZ, time);
            // Set internal state
            if (!positionLock)
LM's avatar
LM committed
585
            {
LM's avatar
LM committed
586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605
                // If position was not locked before, notify positive
                GAudioOutput::instance()->notifyPositive();
            }
            positionLock = true;
            isGlobalPositionKnown = true;
            //TODO fix this hack for forwarding of global position for patch antenna tracking
            forwardMessage(message);
        }
            break;
        case MAVLINK_MSG_ID_GPS_RAW_INT:
        {
            mavlink_gps_raw_int_t pos;
            mavlink_msg_gps_raw_int_decode(&message, &pos);

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

            if (pos.fix_type > 2)
LM's avatar
LM committed
606
            {
LM's avatar
LM committed
607
                emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
LM's avatar
LM committed
608 609 610 611
                latitude = pos.lat/(double)1E7;
                longitude = pos.lon/(double)1E7;
                altitude = pos.alt/1000.0;
                positionLock = true;
612
                isGlobalPositionKnown = true;
LM's avatar
LM committed
613

LM's avatar
LM committed
614 615 616
                // Check for NaN
                int alt = pos.alt;
                if (!isnan(alt) && !isinf(alt))
617
                {
LM's avatar
LM committed
618 619 620 621 622
                    alt = 0;
                    //emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE");
                }
                // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
                // Smaller than threshold and not NaN
LM's avatar
LM committed
623

LM's avatar
LM committed
624
                float vel = pos.vel/100.0f;
LM's avatar
LM committed
625

LM's avatar
LM committed
626 627 628 629 630 631 632 633 634
                if (vel < 1000000 && !isnan(vel) && !isinf(vel))
                {
                    // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, 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(vel));
lm's avatar
lm committed
635 636
                }
            }
LM's avatar
LM committed
637
        }
LM's avatar
LM committed
638
            break;
639
        case MAVLINK_MSG_ID_GPS_STATUS:
LM's avatar
LM committed
640 641 642 643
        {
            mavlink_gps_status_t pos;
            mavlink_msg_gps_status_decode(&message, &pos);
            for(int i = 0; i < (int)pos.satellites_visible; i++)
644
            {
LM's avatar
LM committed
645
                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]));
646
            }
LM's avatar
LM committed
647
        }
LM's avatar
LM committed
648
            break;
649
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
LM's avatar
LM committed
650 651 652 653 654
        {
            mavlink_gps_global_origin_t pos;
            mavlink_msg_gps_global_origin_decode(&message, &pos);
            emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
        }
LM's avatar
LM committed
655
            break;
656
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
LM's avatar
LM committed
657 658 659 660 661 662 663 664 665 666 667 668 669
        {
            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);
        }
LM's avatar
LM committed
670
            break;
671
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
LM's avatar
LM committed
672 673 674 675 676 677 678 679 680 681 682 683 684
        {
            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
685
            break;
686
        case MAVLINK_MSG_ID_PARAM_VALUE:
LM's avatar
LM committed
687 688 689 690 691 692 693 694 695 696 697 698
        {
            mavlink_param_value_t value;
            mavlink_msg_param_value_decode(&message, &value);
            QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
            QString parameterName = QString(bytes);
            int component = message.compid;
            mavlink_param_union_t val;
            val.param_float = value.param_value;
            val.type = value.param_type;

            // Insert component if necessary
            if (!parameters.contains(component))
699
            {
LM's avatar
LM committed
700 701
                parameters.insert(component, new QMap<QString, QVariant>());
            }
702

LM's avatar
LM committed
703 704
            // Insert parameter into registry
            if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
705

LM's avatar
LM committed
706 707 708 709 710 711 712 713 714 715 716 717
            // Insert with correct type
            switch (value.param_type)
            {
            case MAVLINK_TYPE_FLOAT:
            {
                // Variant
                QVariant param(val.param_float);
                parameters.value(component)->insert(parameterName, param);
                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, param);
                emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                qDebug() << "RECEIVED PARAM:" << param;
LM's avatar
LM committed
718
            }
LM's avatar
LM committed
719 720 721 722 723 724 725 726 727 728
                break;
            case MAVLINK_TYPE_UINT32_T:
            {
                // Variant
                QVariant param(val.param_uint32);
                parameters.value(component)->insert(parameterName, param);
                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, param);
                emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                qDebug() << "RECEIVED PARAM:" << param;
LM's avatar
LM committed
729
            }
LM's avatar
LM committed
730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745
                break;
            case MAVLINK_TYPE_INT32_T:
            {
                // Variant
                QVariant param(val.param_int32);
                parameters.value(component)->insert(parameterName, param);
                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, param);
                emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                qDebug() << "RECEIVED PARAM:" << param;
            }
                break;
            default:
                qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
            }
        }
LM's avatar
LM committed
746
            break;
747 748 749
        case MAVLINK_MSG_ID_COMMAND_ACK:
            mavlink_command_ack_t ack;
            mavlink_msg_command_ack_decode(&message, &ack);
750 751
            if (ack.result == 1)
            {
752
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
753 754 755
            }
            else
            {
756
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
757 758
            }
            break;
LM's avatar
LM committed
759
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
LM's avatar
LM committed
760 761 762 763 764 765
        {
            mavlink_roll_pitch_yaw_thrust_setpoint_t out;
            mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
            quint64 time = getUnixTimeFromMs(out.time_boot_ms);
            emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
        }
LM's avatar
LM committed
766
            break;
lm's avatar
lm committed
767
        case MAVLINK_MSG_ID_MISSION_COUNT:
LM's avatar
LM committed
768 769 770 771
        {
            mavlink_mission_count_t wpc;
            mavlink_msg_mission_count_decode(&message, &wpc);
            if (wpc.target_system == mavlink->getSystemId())
772
            {
LM's avatar
LM committed
773
                waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
pixhawk's avatar
pixhawk committed
774
            }
LM's avatar
LM committed
775 776 777 778 779
            else
            {
                qDebug() << "Got waypoint message, but was not for me";
            }
        }
LM's avatar
LM committed
780
            break;
pixhawk's avatar
pixhawk committed
781

lm's avatar
lm committed
782
        case MAVLINK_MSG_ID_MISSION_ITEM:
LM's avatar
LM committed
783 784 785 786 787
        {
            mavlink_mission_item_t wp;
            mavlink_msg_mission_item_decode(&message, &wp);
            //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
            if(wp.target_system == mavlink->getSystemId())
788
            {
LM's avatar
LM committed
789 790 791 792 793
                waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
            }
            else
            {
                qDebug() << "Got waypoint message, but was not for me";
794
            }
LM's avatar
LM committed
795
        }
LM's avatar
LM committed
796
            break;
pixhawk's avatar
pixhawk committed
797

lm's avatar
lm committed
798
        case MAVLINK_MSG_ID_MISSION_ACK:
LM's avatar
LM committed
799 800 801 802
        {
            mavlink_mission_ack_t wpa;
            mavlink_msg_mission_ack_decode(&message, &wpa);
            if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
803
            {
LM's avatar
LM committed
804
                waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
805
            }
LM's avatar
LM committed
806
        }
LM's avatar
LM committed
807
            break;
808

lm's avatar
lm committed
809
        case MAVLINK_MSG_ID_MISSION_REQUEST:
LM's avatar
LM committed
810 811 812 813
        {
            mavlink_mission_request_t wpr;
            mavlink_msg_mission_request_decode(&message, &wpr);
            if(wpr.target_system == mavlink->getSystemId())
814
            {
LM's avatar
LM committed
815
                waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
pixhawk's avatar
pixhawk committed
816
            }
LM's avatar
LM committed
817 818 819
            else
            {
                qDebug() << "Got waypoint message, but was not for me";
pixhawk's avatar
pixhawk committed
820
            }
LM's avatar
LM committed
821
        }
LM's avatar
LM committed
822
            break;
pixhawk's avatar
pixhawk committed
823

lm's avatar
lm committed
824
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
LM's avatar
LM committed
825 826 827 828 829 830 831 832
        {
            mavlink_mission_item_reached_t wpr;
            mavlink_msg_mission_item_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);
        }
LM's avatar
LM committed
833
            break;
pixhawk's avatar
pixhawk committed
834

lm's avatar
lm committed
835
        case MAVLINK_MSG_ID_MISSION_CURRENT:
LM's avatar
LM committed
836 837 838 839 840
        {
            mavlink_mission_current_t wpc;
            mavlink_msg_mission_current_decode(&message, &wpc);
            waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
        }
LM's avatar
LM committed
841
            break;
pixhawk's avatar
pixhawk committed
842

843
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
LM's avatar
LM committed
844
        {
845
            if (multiComponentSourceDetected && wrongComponent)
846
            {
847
                break;
LM's avatar
LM committed
848
            }
LM's avatar
LM committed
849 850 851 852
            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());
        }
LM's avatar
LM committed
853
            break;
854
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
LM's avatar
LM committed
855 856 857 858 859
        {
            mavlink_set_local_position_setpoint_t p;
            mavlink_msg_set_local_position_setpoint_decode(&message, &p);
            emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw);
        }
860
            break;
861
        case MAVLINK_MSG_ID_STATUSTEXT:
LM's avatar
LM committed
862 863 864 865 866 867 868 869 870 871 872
        {
            QByteArray b;
            b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
            mavlink_msg_statustext_get_text(&message, 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);
        }
LM's avatar
LM committed
873
            break;
874
#ifdef MAVLINK_ENABLED_PIXHAWK
875
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
LM's avatar
LM committed
876 877 878 879 880 881 882 883 884 885 886 887 888
        {
            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;
            imageWidth = p.width;
            imageHeight = p.height;
            imageStart = QGC::groundTimeMilliseconds();
        }
LM's avatar
LM committed
889
            break;
890

891
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
LM's avatar
LM committed
892 893 894 895 896
        {
            mavlink_encapsulated_data_t img;
            mavlink_msg_encapsulated_data_decode(&message, &img);
            int seq = img.seqnr;
            int pos = seq * imagePayload;
LM's avatar
LM committed
897

LM's avatar
LM committed
898 899 900 901 902 903 904
            // Check if we have a valid transaction
            if (imagePackets == 0)
            {
                // NO VALID TRANSACTION - ABORT
                // Restart statemachine
                imagePacketsArrived = 0;
            }
905

LM's avatar
LM committed
906 907 908 909
            for (int i = 0; i < imagePayload; ++i)
            {
                if (pos <= imageSize) {
                    imageRecBuffer[pos] = img.data[i];
LM's avatar
LM committed
910
                }
LM's avatar
LM committed
911 912
                ++pos;
            }
913

LM's avatar
LM committed
914
            ++imagePacketsArrived;
915

LM's avatar
LM committed
916 917 918 919 920 921 922
            // emit signal if all packets arrived
            if ((imagePacketsArrived >= imagePackets))
            {
                // Restart statemachine
                imagePacketsArrived = 0;
                emit imageReady(this);
                qDebug() << "imageReady emitted. all packets arrived";
923
            }
LM's avatar
LM committed
924
        }
LM's avatar
LM committed
925
            break;
926
#endif
LM's avatar
LM committed
927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983
            //        case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT:
            //        {
            //            mavlink_object_detection_event_t event;
            //            mavlink_msg_object_detection_event_decode(&message, &event);
            //            QString str(event.name);
            //            emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance);
            //        }
            //        break;
            // 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++)
            //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
            //                    break;
            //                case 1:
            //                    for (int i = 0; i < 16; i++)
            //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
            //                    break;
            //                case 2:
            //                    for (int i = 0; i < 16; i++)
            //                        // FIXME REMOVE LATER 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++)
            //                        // FIXME REMOVE LATER 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++)
            //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
            //                    break;
            //                case 5:
            //                    for (int i = 0; i < 8; i++)
            //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
            //                    break;
            //                case 6:
            //                    for (int i = 0; i < 8; i++)
            //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
            //                    break;
            //                }
            //            }
            //        }
            //        break;
lm's avatar
lm committed
984
#ifdef MAVLINK_ENABLED_UALBERTA
985
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
LM's avatar
LM committed
986 987 988 989 990 991 992 993 994 995 996
        {
            mavlink_nav_filter_bias_t bias;
            mavlink_msg_nav_filter_bias_decode(&message, &bias);
            quint64 time = getUnixTime();
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time);
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time);
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time);
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time);
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time);
            // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time);
        }
LM's avatar
LM committed
997
            break;
998
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
LM's avatar
LM committed
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
        {
            mavlink_radio_calibration_t radioMsg;
            mavlink_msg_radio_calibration_decode(&message, &radioMsg);
            QVector<uint16_t> aileron;
            QVector<uint16_t> elevator;
            QVector<uint16_t> rudder;
            QVector<uint16_t> gyro;
            QVector<uint16_t> pitch;
            QVector<uint16_t> throttle;

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

            QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
            emit radioCalibrationReceived(radioData);
            delete radioData;
        }
LM's avatar
LM committed
1026
            break;
1027

1028
#endif
LM's avatar
LM committed
1029
            // Messages to ignore
lm's avatar
lm committed
1030 1031 1032 1033 1034 1035 1036 1037
        case MAVLINK_MSG_ID_RAW_IMU:
        case MAVLINK_MSG_ID_SCALED_IMU:
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
        case MAVLINK_MSG_ID_RAW_PRESSURE:
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
        case MAVLINK_MSG_ID_OPTICAL_FLOW:
        case MAVLINK_MSG_ID_DEBUG_VECT:
LM's avatar
LM committed
1038
        case MAVLINK_MSG_ID_DEBUG:
1039 1040
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
1041
            break;
1042
        default:
LM's avatar
LM committed
1043 1044
        {
            if (!unknownPackets.contains(message.msgid))
1045
            {
LM's avatar
LM committed
1046 1047 1048 1049 1050 1051
                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
1052
            }
LM's avatar
LM committed
1053
        }
LM's avatar
LM committed
1054
            break;
pixhawk's avatar
pixhawk committed
1055 1056 1057 1058
        }
    }
}

1059
#if defined(QGC_PROTOBUF_ENABLED)
1060 1061
void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message)
{
LM's avatar
LM committed
1062 1063 1064 1065
    if (!link)
    {
        return;
    }
1066 1067 1068 1069 1070
    if (!links->contains(link))
    {
        addLink(link);
    }

1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105
    const google::protobuf::Descriptor* descriptor = message->GetDescriptor();
    if (!descriptor)
    {
        return;
    }

    const google::protobuf::FieldDescriptor* headerField = descriptor->FindFieldByName("header");
    if (!headerField)
    {
        return;
    }

    const google::protobuf::Descriptor* headerDescriptor = headerField->message_type();
    if (!headerDescriptor)
    {
        return;
    }

    const google::protobuf::FieldDescriptor* sourceSysIdField = headerDescriptor->FindFieldByName("source_sysid");
    if (!sourceSysIdField)
    {
        return;
    }

    const google::protobuf::Reflection* reflection = message->GetReflection();
    const google::protobuf::Message& headerMsg = reflection->GetMessage(*message, headerField);
    const google::protobuf::Reflection* headerReflection = headerMsg.GetReflection();

    int source_sysid = headerReflection->GetInt32(headerMsg, sourceSysIdField);

    if (source_sysid != uasId)
    {
        return;
    }

1106
#ifdef QGC_USE_PIXHAWK_MESSAGES
1107 1108
    if (message->GetTypeName() == pointCloud.GetTypeName())
    {
1109
        receivedPointCloudTimestamp = QGC::groundTimeSeconds();
1110
        pointCloudMutex.lock();
1111
        pointCloud.CopyFrom(*message);
1112
        pointCloudMutex.unlock();
1113
        emit pointCloudChanged(this);
1114
    }
1115 1116
    else if (message->GetTypeName() == rgbdImage.GetTypeName())
    {
1117
        receivedRGBDImageTimestamp = QGC::groundTimeSeconds();
1118
        rgbdImageMutex.lock();
1119
        rgbdImage.CopyFrom(*message);
1120
        rgbdImageMutex.unlock();
1121
        emit rgbdImageChanged(this);
1122
    }
1123 1124
    else if (message->GetTypeName() == obstacleList.GetTypeName())
    {
1125
        receivedObstacleListTimestamp = QGC::groundTimeSeconds();
1126
        obstacleListMutex.lock();
1127
        obstacleList.CopyFrom(*message);
1128
        obstacleListMutex.unlock();
1129 1130
        emit obstacleListChanged(this);
    }
1131 1132
    else if (message->GetTypeName() == path.GetTypeName())
    {
1133
        receivedPathTimestamp = QGC::groundTimeSeconds();
1134
        pathMutex.lock();
1135
        path.CopyFrom(*message);
1136
        pathMutex.unlock();
1137 1138
        emit pathChanged(this);
    }
1139
#endif
1140 1141 1142 1143
}

#endif

1144 1145
void UAS::setHomePosition(double lat, double lon, double alt)
{
1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174
    QMessageBox msgBox;
    msgBox.setIcon(QMessageBox::Warning);
    msgBox.setText("Setting new World Coordinate Frame Origin");
    msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location");
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();

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


    if (ret == QMessageBox::Yes)
    {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 0, 0, 0, 0, lat, lon, alt);
        // Send message twice to increase chance that it reaches its goal
        sendMessage(msg);

        // Send new home position to UAS
        mavlink_set_gps_global_origin_t home;
        home.target_system = uasId;
        home.latitude = lat*1E7;
        home.longitude = lon*1E7;
        home.altitude = alt*1000;
        qDebug() << "lat:" << home.latitude << " lon:" << home.longitude;
        mavlink_msg_set_gps_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
        sendMessage(msg);
    }
1175 1176
}

1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190
void UAS::setLocalOriginAtCurrentGPSPosition()
{
    QMessageBox msgBox;
    msgBox.setIcon(QMessageBox::Warning);
    msgBox.setText("Setting new World Coordinate Frame Origin");
    msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location");
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();

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


1191 1192
    if (ret == QMessageBox::Yes)
    {
1193 1194 1195 1196
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 1, 0, 0, 0, 0, 0, 0);
        // Send message twice to increase chance that it reaches its goal
        sendMessage(msg);
1197 1198 1199
    }
}

pixhawk's avatar
pixhawk committed
1200 1201
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1202
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1203
    mavlink_message_t msg;
LM's avatar
LM committed
1204
    mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw/M_PI*180.0);
pixhawk's avatar
pixhawk committed
1205
    sendMessage(msg);
1206
#else
lm's avatar
lm committed
1207 1208 1209 1210
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1211
#endif
pixhawk's avatar
pixhawk committed
1212 1213
}

pixhawk's avatar
pixhawk committed
1214 1215
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1216
#ifdef MAVLINK_ENABLED_PIXHAWK
1217
    mavlink_message_t msg;
1218
    mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
1219
    sendMessage(msg);
lm's avatar
lm committed
1220
#else
1221 1222 1223 1224
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1225 1226 1227 1228
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1229
{
1230 1231
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1232
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1, 0, 0, 0);
1233
    sendMessage(msg);
lm's avatar
lm committed
1234 1235
}

1236
void UAS::startDataRecording()
lm's avatar
lm committed
1237
{
1238
    mavlink_message_t msg;
1239
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2, 0, 0, 0);
1240
    sendMessage(msg);
lm's avatar
lm committed
1241 1242 1243 1244
}

void UAS::stopDataRecording()
{
1245
    mavlink_message_t msg;
1246
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0, 0, 0, 0);
1247
    sendMessage(msg);
lm's avatar
lm committed
1248 1249
}

pixhawk's avatar
pixhawk committed
1250 1251
void UAS::startMagnetometerCalibration()
{
1252 1253
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1254
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0, 0, 0, 0);
1255
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1256 1257 1258 1259
}

void UAS::startGyroscopeCalibration()
{
1260 1261
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1262
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0, 0, 0, 0);
1263
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1264 1265 1266 1267
}

void UAS::startPressureCalibration()
{
1268 1269
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1270
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0, 0, 0, 0);
1271
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1272 1273
}

LM's avatar
LM committed
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
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
LM's avatar
LM committed
1301
    else if (time < 1261440000000000)
LM's avatar
LM committed
1302
#endif
LM's avatar
LM committed
1303
    {
LM's avatar
LM committed
1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318
        //        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;
    }
}

1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331
/**
 * @warning If attitudeStamped is enabled, this function will not actually return the precise time stamp
 *          of this measurement augmented to UNIX time, but will MOVE the timestamp IN TIME to match
 *          the last measured attitude. There is no reason why one would want this, except for
 *          system setups where the onboard clock is not present or broken and datasets should
 *          be collected that are still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED
 *          RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
 */
quint64 UAS::getUnixTimeFromMs(quint64 time)
{
    return getUnixTime(time*1000);
}

LM's avatar
LM committed
1332 1333 1334 1335 1336 1337 1338 1339
/**
 * @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!
 */
1340 1341
quint64 UAS::getUnixTime(quint64 time)
{
1342
    quint64 ret = 0;
LM's avatar
LM committed
1343 1344
    if (attitudeStamped)
    {
1345
        ret = lastAttitude;
LM's avatar
LM committed
1346
    }
1347 1348
    if (time == 0)
    {
1349
        ret = QGC::groundTimeMilliseconds();
1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366
    }
    // 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
1367
#ifndef _MSC_VER
1368
    else if (time < 1261440000000000LLU)
1369
#else
LM's avatar
LM committed
1370
    else if (time < 1261440000000000)
1371
#endif
LM's avatar
LM committed
1372
    {
LM's avatar
LM committed
1373
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1374 1375
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1376
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1377
        }
1378
        ret = time/1000 + onboardTimeOffset;
1379 1380 1381
    }
    else
    {
1382 1383
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1384
        ret = time/1000;
1385
    }
1386
    return ret;
1387 1388
}

1389 1390
QList<QString> UAS::getParameterNames(int component)
{
1391 1392
    if (parameters.contains(component))
    {
1393
        return parameters.value(component)->keys();
1394 1395 1396
    }
    else
    {
1397 1398 1399 1400 1401 1402 1403 1404 1405
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1406
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1407
{
LM's avatar
LM committed
1408 1409 1410 1411 1412
    //this->mode = mode; //no call assignament, update receive message from UAS
    mavlink_message_t msg;
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode, (uint16_t)navMode);
    sendMessage(msg);
    qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
1413 1414 1415 1416 1417
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1418 1419 1420 1421
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1422
            sendMessage(link, message);
1423 1424 1425
        }
        else
        {
1426 1427 1428
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1429 1430 1431
    }
}

1432 1433 1434 1435
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1436

1437 1438 1439 1440
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1441
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1442 1443 1444 1445 1446 1447
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1448
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1449 1450
                        sendMessage(serial, message);
                    }
1451 1452 1453 1454 1455 1456
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1457 1458
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1459
    if(!link) return;
pixhawk's avatar
pixhawk committed
1460 1461 1462
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1463
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1464 1465
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
pixhawk's avatar
pixhawk committed
1466
    // If link is connected
1467 1468
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1469 1470 1471 1472 1473 1474 1475 1476
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1477
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1478
{
1479
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1480 1481
}

1482 1483
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1484 1485
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
LM's avatar
LM committed
1486 1487 1488 1489 1490 1491 1492 1493
        switch (mode)
        {
        case 0:
            return QString("PREFLIGHT");
            break;
        default:
            return QString("UNKNOWN");
        }
lm's avatar
lm committed
1494 1495 1496 1497 1498 1499 1500 1501 1502
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1503 1504
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1505 1506
}

pixhawk's avatar
pixhawk committed
1507 1508
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1509 1510
    switch (statusCode)
    {
lm's avatar
lm committed
1511
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1512
        uasState = tr("UNINIT");
1513
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1514
        break;
lm's avatar
lm committed
1515
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1516
        uasState = tr("BOOT");
1517
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1518
        break;
lm's avatar
lm committed
1519
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1520
        uasState = tr("CALIBRATING");
1521
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1522
        break;
lm's avatar
lm committed
1523
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1524
        uasState = tr("ACTIVE");
1525
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1526
        break;
lm's avatar
lm committed
1527 1528
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1529
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1530 1531
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1532
        uasState = tr("CRITICAL");
1533
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1534
        break;
lm's avatar
lm committed
1535
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1536
        uasState = tr("EMERGENCY");
1537
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1538
        break;
James Goppert's avatar
James Goppert committed
1539
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1540 1541 1542
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1543

lm's avatar
lm committed
1544
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1545
        uasState = tr("SHUTDOWN");
1546
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1547
        break;
1548

lm's avatar
lm committed
1549
    default:
pixhawk's avatar
pixhawk committed
1550
        uasState = tr("UNKNOWN");
1551
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1552 1553 1554 1555
        break;
    }
}

1556 1557
QImage UAS::getImage()
{
LM's avatar
LM committed
1558 1559 1560 1561 1562 1563 1564
#ifdef MAVLINK_ENABLED_PIXHAWK

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

    // RAW greyscale
    if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
    {
LM's avatar
LM committed
1565 1566
        // TODO FIXME
        int imgColors = 255;//imageSize/(imageWidth*imageHeight);
LM's avatar
LM committed
1567 1568 1569 1570
        //const int headerSize = 15;

        // Construct PGM header
        QString header("P5\n%1 %2\n%3\n");
LM's avatar
LM committed
1571
        header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
LM's avatar
LM committed
1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596

        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)
    {
LM's avatar
LM committed
1597
        if (!image.loadFromData(imageRecBuffer))
LM's avatar
LM committed
1598
        {
LM's avatar
LM committed
1599
            qDebug() << "Loading data from image buffer failed!";
LM's avatar
LM committed
1600 1601
        }
    }
1602 1603
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1604
    //imageRecBuffer.clear();
1605
    return image;
1606
#else
LM's avatar
LM committed
1607
    return QImage();
LM's avatar
LM committed
1608
#endif
1609

1610 1611 1612 1613
}

void UAS::requestImage()
{
1614
#ifdef MAVLINK_ENABLED_PIXHAWK
1615 1616
    qDebug() << "trying to get an image from the uas...";

1617 1618 1619
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1620
        mavlink_message_t msg;
LM's avatar
LM committed
1621
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50);
1622 1623
        sendMessage(msg);
    }
1624
#endif
1625
}
pixhawk's avatar
pixhawk committed
1626 1627 1628 1629 1630 1631 1632 1633 1634


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1635
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1636
{
1637 1638
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1639
        return 0;
1640 1641 1642
    }
    else
    {
LM's avatar
LM committed
1643
        return QGC::groundTimeMilliseconds() - startTime;
pixhawk's avatar
pixhawk committed
1644 1645 1646
    }
}

1647
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1648 1649 1650 1651
{
    return commStatus;
}

1652 1653 1654
void UAS::requestParameters()
{
    mavlink_message_t msg;
LM's avatar
LM committed
1655
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
1656
    sendMessage(msg);
1657 1658
}

1659
void UAS::writeParametersToStorage()
1660
{
1661
    mavlink_message_t msg;
1662
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
pixhawk's avatar
pixhawk committed
1663
    qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
1664
    sendMessage(msg);
1665 1666 1667 1668
}

void UAS::readParametersFromStorage()
{
1669
    mavlink_message_t msg;
1670
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
1671
    sendMessage(msg);
lm's avatar
lm committed
1672 1673
}

1674
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1675 1676
{
    // Buffers to write data to
1677
    mavlink_message_t msg;
1678
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1679 1680
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1681
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1682 1683
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1684 1685
    // 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
1686 1687
    stream.req_message_rate = 0;
    // Start / stop the message
1688
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1689 1690 1691 1692 1693
    // 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
1694
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1695 1696
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1697 1698
}

1699
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1700 1701 1702
{
    // Buffers to write data to
    mavlink_message_t msg;
1703
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1704
    // Select the message to request from now on
1705
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1706
    // Select the update rate in Hz the message should be send
1707
    stream.req_message_rate = rate;
lm's avatar
lm committed
1708
    // Start / stop the message
1709
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1710 1711 1712 1713 1714
    // 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
1715
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1716 1717
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1718 1719
}

1720
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1721
{
1722 1723 1724 1725
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1726
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1727
    // Select the update rate in Hz the message should be send
1728
    stream.req_message_rate = rate;
1729
    // Start / stop the message
1730
    stream.start_stop = (rate) ? 1 : 0;
1731 1732 1733 1734 1735 1736
    // 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);
1737 1738
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1739
}
1740

1741
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1742
{
1743 1744 1745 1746 1747
#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
1748 1749 1750
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1751
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1752
    // Select the update rate in Hz the message should be send
1753
    stream.req_message_rate = rate;
1754
    // Start / stop the message
1755
    stream.start_stop = (rate) ? 1 : 0;
1756 1757 1758 1759 1760 1761
    // 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);
1762 1763
    // Send message twice to increase chance of reception
    sendMessage(msg);
1764
#endif
lm's avatar
lm committed
1765 1766
}

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

lm's avatar
lm committed
1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808
//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);
//}
1809

1810
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1811 1812 1813 1814 1815
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1816
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1817
    // Select the update rate in Hz the message should be send
1818
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1819
    // Start / stop the message
1820
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1821 1822 1823 1824 1825 1826 1827 1828 1829 1830
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
}

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

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

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

lm's avatar
lm committed
1897 1898 1899 1900 1901 1902 1903
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1904
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
lm's avatar
lm committed
1905
{
1906 1907
    if (!id.isNull())
    {
1908 1909
        mavlink_message_t msg;
        mavlink_param_set_t p;
1910 1911 1912 1913 1914 1915 1916
        mavlink_param_union_t union_value;

        // Assign correct value based on QVariant
        switch (value.type())
        {
        case QVariant::Int:
            union_value.param_int32 = value.toInt();
1917
            p.param_type = MAVLINK_TYPE_INT32_T;
1918 1919 1920
            break;
        case QVariant::UInt:
            union_value.param_uint32 = value.toUInt();
1921
            p.param_type = MAVLINK_TYPE_UINT32_T;
1922 1923 1924
            break;
        case QMetaType::Float:
            union_value.param_float = value.toFloat();
1925
            p.param_type = MAVLINK_TYPE_FLOAT;
1926 1927 1928 1929 1930 1931 1932
            break;
        default:
            qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
            return;
        }

        p.param_value = union_value.param_float;
1933 1934 1935
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

1936 1937
        qDebug() << "SENT PARAM:" << value;

1938
        // Copy string into buffer, ensuring not to exceed the buffer size
1939 1940
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1941
            // String characters
1942 1943
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1944 1945
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1946 1947 1948 1949 1950
            //        // 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';
            //        }
1951
            // Zero fill
1952 1953
            else
            {
1954 1955
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1956
        }
1957 1958
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1959
    }
1960 1961
}

1962 1963 1964 1965 1966 1967 1968 1969 1970 1971 1972 1973 1974 1975
void UAS::requestParameter(int component, int id)
{
    // Request parameter, use parameter name to request it
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
    read.param_index = id;
    read.param_id[0] = '\0'; // Enforce null termination
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << id;
}

1976
void UAS::requestParameter(int component, const QString& parameter)
1977
{
1978
    // Request parameter, use parameter name to request it
1979 1980
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
1981 1982 1983 1984 1985 1986 1987 1988
    read.param_index = -1;
    // Copy full param name or maximum max field size
    if (parameter.length() > MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)
    {
        emit textMessageReceived(uasId, 0, 255, QString("QGC WARNING: Parameter name %1 is more than %2 bytes long. This might lead to errors and mishaps!").arg(parameter).arg(MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN-1));
    }
    memcpy(read.param_id, parameter.toStdString().c_str(), qMax(parameter.length(), MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN));
    read.param_id[15] = '\0'; // Enforce null termination
1989 1990 1991 1992
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
1993
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
1994 1995
}

1996 1997 1998 1999
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
2000 2001 2002 2003
    if (airframe == 0)
    {
        switch (systemType)
        {
lm's avatar
lm committed
2004
        case MAV_TYPE_FIXED_WING:
2005 2006
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
lm's avatar
lm committed
2007
        case MAV_TYPE_QUADROTOR:
2008 2009 2010 2011 2012 2013 2014
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

2015 2016
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
2017 2018 2019 2020 2021 2022 2023
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
2024 2025
}

lm's avatar
lm committed
2026 2027 2028
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
2029
    mavlink_command_long_t cmd;
2030 2031 2032 2033 2034 2035
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
2036 2037 2038
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
2039 2040
    cmd.target_system = uasId;
    cmd.target_component = 0;
2041
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
2042 2043 2044
    sendMessage(msg);
}

2045 2046 2047 2048
void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component)
{
    mavlink_message_t msg;
    mavlink_command_long_t cmd;
2049 2050 2051 2052 2053 2054
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
2055 2056 2057
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
2058 2059
    cmd.target_system = uasId;
    cmd.target_component = component;
2060
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
2061 2062 2063
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
2064
/**
lm's avatar
lm committed
2065
 * Launches the system
pixhawk's avatar
pixhawk committed
2066 2067 2068 2069
 *
 **/
void UAS::launch()
{
2070
    mavlink_message_t msg;
2071
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_NAV_TAKEOFF, 1, 0, 0, 0, 0, 0, 0, 0);
2072
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2073 2074 2075 2076 2077 2078
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
2079
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
2080
{
2081
    mavlink_message_t msg;
2082
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
2083
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2084 2085 2086 2087 2088 2089
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
2090
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
2091
{
2092
    mavlink_message_t msg;
2093
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
2094
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2095 2096 2097 2098 2099 2100 2101 2102 2103 2104 2105 2106 2107 2108
}

void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust)
{
    // Scale values
    double rollPitchScaling = 0.2f;
    double yawScaling = 0.5f;
    double thrustScaling = 1.0f;

    manualRollAngle = roll * rollPitchScaling;
    manualPitchAngle = pitch * rollPitchScaling;
    manualYawAngle = yaw * yawScaling;
    manualThrust = thrust * thrustScaling;

LM's avatar
LM committed
2109 2110
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
2111
    {
2112 2113 2114 2115
        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
2116

LM's avatar
LM committed
2117
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
2118 2119 2120
    }
    else
    {
2121 2122
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2123 2124
}

2125 2126 2127 2128 2129
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2130 2131
void UAS::receiveButton(int buttonIndex)
{
2132 2133
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2134
    case 0:
pixhawk's avatar
pixhawk committed
2135

pixhawk's avatar
pixhawk committed
2136 2137
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2138

pixhawk's avatar
pixhawk committed
2139 2140 2141 2142 2143
        break;
    default:

        break;
    }
2144
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2145 2146 2147

}

2148

pixhawk's avatar
pixhawk committed
2149 2150
void UAS::halt()
{
2151 2152 2153
    mavlink_message_t msg;
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_HOLD, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2154 2155 2156 2157
}

void UAS::go()
{
2158 2159 2160
    mavlink_message_t msg;
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2161 2162 2163 2164 2165
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
2166 2167 2168 2169 2170 2171 2172 2173 2174
    mavlink_message_t msg;

    double latitude = UASManager::instance()->getHomeLatitude();
    double longitude = UASManager::instance()->getHomeLongitude();
    double altitude = UASManager::instance()->getHomeAltitude();
    int frame = UASManager::instance()->getHomeFrame();

    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, frame, 0, latitude, longitude, altitude);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2175 2176 2177 2178 2179 2180 2181 2182
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2183 2184
    // FIXME MAVLINKV10PORTINGNEEDED
    halt();
pixhawk's avatar
pixhawk committed
2185 2186 2187
}

/**
lm's avatar
lm committed
2188
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2189 2190 2191 2192 2193 2194
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
2195
    halt();
lm's avatar
lm committed
2196
    // FIXME MAVLINKV10PORTINGNEEDED
LM's avatar
LM committed
2197 2198 2199 2200 2201 2202 2203 2204 2205 2206 2207 2208 2209 2210 2211 2212 2213 2214 2215 2216 2217 2218 2219 2220
    //    bool result = false;
    //    QMessageBox msgBox;
    //    msgBox.setIcon(QMessageBox::Critical);
    //    msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS");
    //    msgBox.setInformativeText("Do you want to cut power on all systems?");
    //    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    //    msgBox.setDefaultButton(QMessageBox::Cancel);
    //    int ret = msgBox.exec();

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


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

lm's avatar
lm committed
2224 2225 2226 2227 2228
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2229
        startHil();
lm's avatar
lm committed
2230 2231 2232
    }
    else
    {
2233
        stopHil();
lm's avatar
lm committed
2234 2235 2236 2237 2238 2239 2240 2241 2242 2243 2244 2245 2246 2247 2248 2249 2250 2251 2252 2253 2254 2255
    }
}

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


2265 2266
void UAS::startHil()
{
lm's avatar
lm committed
2267 2268
    // Connect Flight Gear Link
    simulation->connectSimulation();
2269
    mavlink_message_t msg;
LM's avatar
LM committed
2270
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
2271
    sendMessage(msg);
2272 2273
}

2274 2275
void UAS::stopHil()
{
lm's avatar
lm committed
2276
    simulation->disconnectSimulation();
2277
    mavlink_message_t msg;
LM's avatar
LM committed
2278
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
2279
    sendMessage(msg);
2280 2281 2282
}


pixhawk's avatar
pixhawk committed
2283 2284
void UAS::shutdown()
{
2285 2286 2287 2288 2289
    bool result = false;
    QMessageBox msgBox;
    msgBox.setIcon(QMessageBox::Critical);
    msgBox.setText("Shutting down the UAS");
    msgBox.setInformativeText("Do you want to shut down the onboard computer?");
lm's avatar
lm committed
2290

2291 2292 2293
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2294

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

2298 2299 2300 2301
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2302
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 0, 2, 0, 0, 0, 0, 0);
2303 2304 2305
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2306 2307
}

2308 2309
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2310
    mavlink_message_t msg;
2311
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 2, 3, 0, yaw, x, y, z);
2312
    sendMessage(msg);
2313 2314
}

pixhawk's avatar
pixhawk committed
2315 2316 2317
/**
 * @return The name of this system as string in human-readable form
 */
2318
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2319 2320
{
    QString result;
2321 2322
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2323
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2324 2325 2326
    }
    else
    {
pixhawk's avatar
pixhawk committed
2327 2328 2329 2330 2331
        result = name;
    }
    return result;
}

2332 2333 2334 2335 2336
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2337 2338 2339
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2340 2341 2342
    uint8_t modeid = id;

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

LM's avatar
LM committed
2344
    // BASE MODE DECODING
pixhawk's avatar
pixhawk committed
2345
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
LM's avatar
LM committed
2346
    {
pixhawk's avatar
pixhawk committed
2347
        mode += "AUTO";
LM's avatar
LM committed
2348
    }
pixhawk's avatar
pixhawk committed
2349
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
LM's avatar
LM committed
2350
    {
LM's avatar
LM committed
2351
        mode += "|GUID";
LM's avatar
LM committed
2352
    }
pixhawk's avatar
pixhawk committed
2353
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
LM's avatar
LM committed
2354
    {
LM's avatar
LM committed
2355
        mode += "|STAB";
LM's avatar
LM committed
2356
    }
pixhawk's avatar
pixhawk committed
2357
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
LM's avatar
LM committed
2358
    {
LM's avatar
LM committed
2359
        mode += "|TEST";
LM's avatar
LM committed
2360
    }
pixhawk's avatar
pixhawk committed
2361
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
LM's avatar
LM committed
2362
    {
LM's avatar
LM committed
2363
        mode += "|MAN";
LM's avatar
LM committed
2364
    }
pixhawk's avatar
pixhawk committed
2365 2366

    if (modeid == 0)
LM's avatar
LM committed
2367
    {
2368
        mode = "PREFLIGHT";
LM's avatar
LM committed
2369 2370 2371
    }

    // ARMED STATE DECODING
pixhawk's avatar
pixhawk committed
2372
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
LM's avatar
LM committed
2373
    {
LM's avatar
LM committed
2374
        mode.prepend("A/");
LM's avatar
LM committed
2375 2376 2377
    }
    else
    {
LM's avatar
LM committed
2378
        mode.prepend("D/");
LM's avatar
LM committed
2379 2380 2381
    }

    // HARDWARE IN THE LOOP DECODING
pixhawk's avatar
pixhawk committed
2382
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
LM's avatar
LM committed
2383 2384
    {
        mode.prepend("HIL:");
2385 2386 2387 2388 2389
    }

    return mode;
}

2390 2391 2392 2393 2394
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2395 2396
void UAS::addLink(LinkInterface* link)
{
2397 2398
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2399
        links->append(link);
2400
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2401 2402 2403
    }
}

2404 2405 2406
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2407 2408
    if (link)
    {
2409 2410 2411 2412
        links->removeAt(links->indexOf(link));
    }
}

LM's avatar
LM committed
2413

pixhawk's avatar
pixhawk committed
2414 2415 2416 2417 2418
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}

LM's avatar
LM committed
2419 2420 2421 2422 2423
QMap<int, QString> UAS::getComponents()
{
    return components;
}

pixhawk's avatar
pixhawk committed
2424 2425 2426 2427 2428 2429


void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2430 2431
    switch (batteryType)
    {
lm's avatar
lm committed
2432
    case NICD:
pixhawk's avatar
pixhawk committed
2433
        break;
lm's avatar
lm committed
2434
    case NIMH:
pixhawk's avatar
pixhawk committed
2435
        break;
lm's avatar
lm committed
2436
    case LIION:
pixhawk's avatar
pixhawk committed
2437
        break;
lm's avatar
lm committed
2438
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2439 2440 2441
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2442
    case LIFE:
pixhawk's avatar
pixhawk committed
2443
        break;
lm's avatar
lm committed
2444
    case AGZN:
pixhawk's avatar
pixhawk committed
2445 2446 2447 2448
        break;
    }
}

2449 2450
void UAS::setBatterySpecs(const QString& specs)
{
2451 2452
    if (specs.length() == 0 || specs.contains("%"))
    {
2453
        batteryRemainingEstimateEnabled = false;
2454
        bool ok;
2455 2456 2457
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2458 2459
        if (ok)
        {
2460
            warnLevelPercent = temp;
2461 2462 2463
        }
        else
        {
2464 2465
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2466 2467 2468
    }
    else
    {
2469 2470 2471 2472 2473
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2474 2475
        if (parts.length() == 3)
        {
2476 2477 2478 2479 2480 2481 2482 2483 2484 2485 2486
            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;
2487 2488 2489
        }
        else
        {
2490 2491
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2492 2493 2494 2495 2496
    }
}

QString UAS::getBatterySpecs()
{
2497 2498
    if (batteryRemainingEstimateEnabled)
    {
2499
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2500 2501 2502
    }
    else
    {
2503 2504
        return QString("%1%").arg(warnLevelPercent);
    }
2505 2506
}

pixhawk's avatar
pixhawk committed
2507 2508
int UAS::calculateTimeRemaining()
{
LM's avatar
LM committed
2509
    quint64 dt = QGC::groundTimeMilliseconds() - startTime;
pixhawk's avatar
pixhawk committed
2510 2511 2512 2513 2514 2515 2516 2517 2518 2519
    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
2520 2521 2522
/**
 * @return charge level in percent - 0 - 100
 */
2523
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2524
{
2525 2526 2527 2528
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2529
            chargeLevel = 0.0f;
2530 2531 2532
        }
        else if (lpVoltage > fullVoltage)
        {
2533
            chargeLevel = 100.0f;
2534 2535 2536
        }
        else
        {
2537 2538
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2539 2540
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2541 2542
}

lm's avatar
lm committed
2543 2544
void UAS::startLowBattAlarm()
{
2545 2546
    if (!lowBattAlarm)
    {
2547
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2548
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2549 2550 2551 2552 2553 2554
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2555 2556
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2557 2558 2559 2560
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}