UAS.cc 92.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
    uasId(id),
    startTime(QGC::groundTimeMilliseconds()),
    commStatus(COMM_DISCONNECTED),
    name(""),
    autopilot(-1),
    links(new QList<LinkInterface*>()),
    unknownPackets(),
    mavlink(protocol),
    waypointManager(this),
    thrustSum(0),
    thrustMax(10),
46 47 48 49
    startVoltage(-1.0f),
    tickVoltage(10.5f),
    lastTickVoltageValue(13.0f),
    tickLowpassVoltage(12.0f),
lm's avatar
lm committed
50 51
    warnVoltage(9.5f),
    warnLevelPercent(20.0f),
52
    currentVoltage(12.6f),
lm's avatar
lm committed
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 78 79 80
    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
81
    #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
82
    receivedOverlayTimestamp(0.0),
83 84
    receivedObstacleListTimestamp(0.0),
    receivedPathTimestamp(0.0),
85 86
    receivedPointCloudTimestamp(0.0),
    receivedRGBDImageTimestamp(0.0),
LM's avatar
LM committed
87
    #endif
lm's avatar
lm committed
88
    paramsOnceRequested(false),
89
    airframe(QGC_AIRFRAME_GENERIC),
lm's avatar
lm committed
90 91 92 93 94 95 96
    attitudeKnown(false),
    paramManager(NULL),
    attitudeStamped(false),
    lastAttitude(0),
    simulation(new QGCFlightGearLink(this)),
    isLocalPositionKnown(false),
    isGlobalPositionKnown(false),
97 98 99
    systemIsArmed(false),
    nedPosGlobalOffset(0,0,0),
    nedAttGlobalOffset(0,0,0)
100

pixhawk's avatar
pixhawk committed
101
{
102 103 104 105 106
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
    }
107
    
108
    color = UASInterface::getNextColor();
109
    
lm's avatar
lm committed
110
    setBatterySpecs(QString("9V,9.5V,12.6V"));
111
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
112
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
113
    statusTimeout->start(500);
114 115
    readSettings(); 
    type = MAV_TYPE_GENERIC;
116 117 118
    // Initial signals
    emit disarmed();
    emit armingChanged(false);
pixhawk's avatar
pixhawk committed
119 120 121 122
}

UAS::~UAS()
{
123
    writeSettings();
pixhawk's avatar
pixhawk committed
124
    delete links;
125
    links=NULL;
126
}
127 128 129 130 131
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
132 133
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
134
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
135 136 137 138 139 140 141 142 143
    settings.endGroup();
    settings.sync();
}

void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
144 145
    this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
    this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
Lorenz Meier's avatar
Lorenz Meier committed
146 147
    if (settings.contains("BATTERY_SPECS"))
    {
148 149
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
150 151 152
    settings.endGroup();
}

153 154 155
void UAS::deleteSettings()
{
    this->name = "";
156
    this->airframe = QGC_AIRFRAME_GENERIC;
157
    this->autopilot = -1;
158
    setBatterySpecs(QString("9V,9.5V,12.6V"));
159 160
}

161
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
162 163 164 165
{
    return uasId;
}

166 167
void UAS::updateState()
{
168 169
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
170 171
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
172 173 174 175
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

176 177
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
178 179
    if (positionLock)
    {
180
        positionLock = false;
181 182 183
    }
    else
    {
lm's avatar
lm committed
184
        if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock)
185
        {
186 187 188 189 190
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
191 192
void UAS::setSelected()
{
193 194
    if (UASManager::instance()->getActiveUAS() != this)
    {
195 196 197 198 199 200 201 202
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

bool UAS::getSelected() const
{
    return (UASManager::instance()->getActiveUAS() == this);
pixhawk's avatar
pixhawk committed
203 204 205 206
}

void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
207
    if (!link) return;
208 209
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
210
        addLink(link);
211
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
212 213
    }

LM's avatar
LM committed
214 215 216 217 218 219 220
    if (!components.contains(message.compid))
    {
        QString componentName;

        switch (message.compid)
        {
        case MAV_COMP_ID_ALL:
LM's avatar
LM committed
221 222 223 224
        {
            componentName = "ANONYMOUS";
            break;
        }
LM's avatar
LM committed
225
        case MAV_COMP_ID_IMU:
LM's avatar
LM committed
226 227 228 229
        {
            componentName = "IMU #1";
            break;
        }
LM's avatar
LM committed
230
        case MAV_COMP_ID_CAMERA:
LM's avatar
LM committed
231 232 233 234
        {
            componentName = "CAMERA";
            break;
        }
LM's avatar
LM committed
235
        case MAV_COMP_ID_MISSIONPLANNER:
LM's avatar
LM committed
236 237 238 239
        {
            componentName = "MISSIONPLANNER";
            break;
        }
LM's avatar
LM committed
240 241 242 243 244 245
        }

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

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

LM's avatar
LM committed
248 249 250 251
    // 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))
252
    {
pixhawk's avatar
pixhawk committed
253 254
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
255

256 257 258
        bool multiComponentSourceDetected = false;
        bool wrongComponent = false;

259 260 261 262 263 264 265 266 267 268 269
        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;
        }

270 271 272
        // Store component ID
        if (componentID[message.msgid] == -1)
        {
273
            // Prefer the first component
274 275 276 277 278 279 280 281 282 283 284 285 286 287 288
            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;


289 290
        switch (message.msgid)
        {
pixhawk's avatar
pixhawk committed
291
        case MAVLINK_MSG_ID_HEARTBEAT:
292
        {
LM's avatar
LM committed
293 294 295 296
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
297
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
298
            emit heartbeat(this);
299 300
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
301 302 303 304 305
			
			// 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);
306 307 308
			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);
309
			
pixhawk's avatar
pixhawk committed
310
            // Set new type if it has changed
311
            if (this->type != state.type)
312
            {
313
                this->type = state.type;
314 315 316 317
                if (airframe == 0)
                {
                    switch (type)
                    {
lm's avatar
lm committed
318
                    case MAV_TYPE_FIXED_WING:
319 320
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
lm's avatar
lm committed
321
                    case MAV_TYPE_QUADROTOR:
322 323
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
324 325 326
                    case MAV_TYPE_HEXAROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
                        break;
327 328 329 330 331
                    default:
                        // Do nothing
                        break;
                    }
                }
332
                this->autopilot = state.autopilot;
pixhawk's avatar
pixhawk committed
333 334
                emit systemTypeSet(this, type);
            }
335

336 337 338 339 340 341 342 343 344 345 346 347 348 349 350
            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();
                }
            }
351

352
            QString audiostring = QString("System %1").arg(uasId);
353 354 355 356 357
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
358

359
            QString audiomodeText = getAudioModeTextFor(static_cast<int>(state.base_mode));
LM's avatar
LM committed
360

361 362

            if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT)
363 364 365 366 367 368
            {
                statechanged = true;
                this->status = state.system_status;
                getStatusForCode((int)state.system_status, uasState, stateDescription);
                emit statusChanged(this, uasState, stateDescription);
                emit statusChanged(this->status);
369

370
                shortStateText = uasState;
371

372 373
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
374

375
            if (this->mode != static_cast<int>(state.base_mode))
376 377
            {
                modechanged = true;
378
                this->mode = static_cast<int>(state.base_mode);
379
                shortModeText = getShortModeTextFor(this->mode);
380

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

383
                modeAudio = " is now in " + audiomodeText;
384
            }
LM's avatar
LM committed
385

386
            if (navMode != state.custom_mode)
387
            {
388 389
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
LM's avatar
LM committed
390
                //navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
391
            }
392

393 394 395 396 397 398 399 400 401 402 403
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
404

405 406 407 408 409 410 411
            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();
412
                GAudioOutput::instance()->say(audiostring.toLower());
413
            }
LM's avatar
LM committed
414
        }
415

416 417 418
            break;
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
LM's avatar
LM committed
419 420 421 422 423 424
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_sys_status_t state;
            mavlink_msg_sys_status_decode(&message, &state);
425

426 427 428 429 430 431 432 433 434
			// 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);
435
            emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);
436 437

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

441
			// Battery charge/time remaining/voltage calculations
LM's avatar
LM committed
442 443
            currentVoltage = state.voltage_battery/1000.0f;
            lpVoltage = filterVoltage(currentVoltage);
444
            tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage;
LM's avatar
LM committed
445

446 447 448 449 450 451 452 453 454
            // We don't want to tick above the threshold
            if (tickLowpassVoltage > tickVoltage)
            {
                lastTickVoltageValue = tickLowpassVoltage;
            }

            if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f)
                    && (lpVoltage < tickVoltage))
            {
455
                GAudioOutput::instance()->say(QString("voltage warning: %1 volt").arg(lpVoltage, 0, 'f', 1, QChar(' ')));
456 457 458 459
                lastTickVoltageValue = tickLowpassVoltage;
            }

            if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage;
LM's avatar
LM committed
460 461 462 463 464 465
            timeRemaining = calculateTimeRemaining();
            if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
            {
                chargeLevel = state.battery_remaining;
            }
            emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
466 467 468 469 470 471 472 473 474
			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);
			}
475

LM's avatar
LM committed
476
            // LOW BATTERY ALARM
477
            if (lpVoltage < warnVoltage && (startVoltage > 0.0f))
LM's avatar
LM committed
478 479
            {
                startLowBattAlarm();
480
            }
LM's avatar
LM committed
481
            else
LM's avatar
LM committed
482
            {
LM's avatar
LM committed
483
                stopLowBattAlarm();
pixhawk's avatar
pixhawk committed
484
            }
485

486 487 488 489 490 491 492
            // control_sensors_enabled:
            // relevant bits: 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control
            emit attitudeControlEnabled(state.onboard_control_sensors_enabled & (1 << 11));
            emit positionYawControlEnabled(state.onboard_control_sensors_enabled & (1 << 12));
            emit positionZControlEnabled(state.onboard_control_sensors_enabled & (1 << 13));
            emit positionXYControlEnabled(state.onboard_control_sensors_enabled & (1 << 14));

493 494 495 496 497 498
			// 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)
			{
499
				state.drop_rate_comm = 10000;
500
			}
501 502
			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);
503
		}
LM's avatar
LM committed
504
            break;
pixhawk's avatar
pixhawk committed
505
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
506 507 508 509
        {
            mavlink_attitude_t attitude;
            mavlink_msg_attitude_decode(&message, &attitude);
            quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
510

LM's avatar
LM committed
511
            emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time);
512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540

            if (!wrongComponent)
            {
                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 attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
            }
LM's avatar
LM committed
541
        }
LM's avatar
LM committed
542
            break;
543 544 545 546 547 548 549 550 551 552 553 554
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET:
        {
            mavlink_local_position_ned_system_global_offset_t offset;
            mavlink_msg_local_position_ned_system_global_offset_decode(&message, &offset);
            nedPosGlobalOffset.setX(offset.x);
            nedPosGlobalOffset.setY(offset.y);
            nedPosGlobalOffset.setZ(offset.z);
            nedAttGlobalOffset.setX(offset.roll);
            nedAttGlobalOffset.setY(offset.pitch);
            nedAttGlobalOffset.setZ(offset.yaw);
        }
            break;
lm's avatar
lm committed
555
        case MAVLINK_MSG_ID_HIL_CONTROLS:
LM's avatar
LM committed
556 557 558 559 560
        {
            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
561
            break;
562
        case MAVLINK_MSG_ID_VFR_HUD:
LM's avatar
LM committed
563 564 565 566 567 568
        {
            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
569

LM's avatar
LM committed
570 571 572 573
            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
574
            }
LM's avatar
LM committed
575 576 577 578

            emit altitudeChanged(uasId, hud.alt);
            emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
        }
LM's avatar
LM committed
579
            break;
lm's avatar
lm committed
580
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
lm's avatar
lm committed
581
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
582
            //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
583 584 585 586
        {
            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
587

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

LM's avatar
LM committed
591

LM's avatar
LM committed
592 593 594 595 596
            if (!wrongComponent)
            {
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
597

LM's avatar
LM committed
598
                // Emit
599

LM's avatar
LM committed
600 601
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
602

LM's avatar
LM committed
603 604 605 606
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
LM's avatar
LM committed
607
                }
LM's avatar
LM committed
608 609
                positionLock = true;
                isLocalPositionKnown = true;
610
            }
LM's avatar
LM committed
611
        }
612 613
            break;
        case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
LM's avatar
LM committed
614 615 616 617 618 619 620
        {
            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
621
            break;
622
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
623 624
            //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
625 626 627 628 629 630 631 632 633 634 635 636
        {
            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);
637

LM's avatar
LM committed
638 639
            // Set internal state
            if (!positionLock)
LM's avatar
LM committed
640
            {
LM's avatar
LM committed
641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658
                // 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);
659 660 661 662 663 664 665 666 667
            
            emit gpsLocalizationChanged(this, pos.fix_type);
            // TODO: track localization state not only for gps but also for other loc. sources
            int loc_type = pos.fix_type;
            if (loc_type == 1)
            {
                loc_type = 0; 
            }
            emit localizationChanged(this, loc_type);
LM's avatar
LM committed
668 669

            if (pos.fix_type > 2)
LM's avatar
LM committed
670
            {
LM's avatar
LM committed
671
                emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
LM's avatar
LM committed
672 673 674 675
                latitude = pos.lat/(double)1E7;
                longitude = pos.lon/(double)1E7;
                altitude = pos.alt/1000.0;
                positionLock = true;
676
                isGlobalPositionKnown = true;
LM's avatar
LM committed
677

LM's avatar
LM committed
678 679 680
                // Check for NaN
                int alt = pos.alt;
                if (!isnan(alt) && !isinf(alt))
681
                {
LM's avatar
LM committed
682 683 684 685 686
                    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
687

LM's avatar
LM committed
688
                float vel = pos.vel/100.0f;
LM's avatar
LM committed
689

LM's avatar
LM committed
690 691 692 693 694 695 696 697 698
                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
699 700
                }
            }
LM's avatar
LM committed
701
        }
LM's avatar
LM committed
702
            break;
703
        case MAVLINK_MSG_ID_GPS_STATUS:
LM's avatar
LM committed
704 705 706 707
        {
            mavlink_gps_status_t pos;
            mavlink_msg_gps_status_decode(&message, &pos);
            for(int i = 0; i < (int)pos.satellites_visible; i++)
708
            {
LM's avatar
LM committed
709
                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]));
710
            }
LM's avatar
LM committed
711
        }
LM's avatar
LM committed
712
            break;
713
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
LM's avatar
LM committed
714 715 716
        {
            mavlink_gps_global_origin_t pos;
            mavlink_msg_gps_global_origin_decode(&message, &pos);
717
            emit homePositionChanged(uasId, pos.latitude / 10000000.0, pos.longitude / 10000000.0, pos.altitude / 1000.0);
LM's avatar
LM committed
718
        }
LM's avatar
LM committed
719
            break;
720
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
LM's avatar
LM committed
721 722 723 724 725 726 727 728 729 730 731 732 733
        {
            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
734
            break;
735
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
LM's avatar
LM committed
736 737 738 739 740 741 742 743 744 745 746 747 748
        {
            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
749
            break;
750
        case MAVLINK_MSG_ID_PARAM_VALUE:
LM's avatar
LM committed
751 752 753 754
        {
            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);
755 756 757
            // Construct a string stopping at the first NUL (0) character, else copy the whole
            // byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe)
            QString parameterName(bytes);
LM's avatar
LM committed
758 759 760 761 762 763 764
            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))
765
            {
LM's avatar
LM committed
766 767
                parameters.insert(component, new QMap<QString, QVariant>());
            }
768

LM's avatar
LM committed
769 770
            // Insert parameter into registry
            if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
771

LM's avatar
LM committed
772 773 774 775 776 777 778 779 780 781 782 783
            // 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
784
            }
LM's avatar
LM committed
785 786 787 788 789 790 791 792 793 794
                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
795
            }
LM's avatar
LM committed
796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811
                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
812
            break;
813 814 815
        case MAVLINK_MSG_ID_COMMAND_ACK:
            mavlink_command_ack_t ack;
            mavlink_msg_command_ack_decode(&message, &ack);
816 817
            if (ack.result == 1)
            {
818
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
819 820 821
            }
            else
            {
822
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
823 824
            }
            break;
LM's avatar
LM committed
825
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
LM's avatar
LM committed
826 827 828 829 830 831
        {
            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
832
            break;
lm's avatar
lm committed
833
        case MAVLINK_MSG_ID_MISSION_COUNT:
LM's avatar
LM committed
834 835 836 837
        {
            mavlink_mission_count_t wpc;
            mavlink_msg_mission_count_decode(&message, &wpc);
            if (wpc.target_system == mavlink->getSystemId())
838
            {
LM's avatar
LM committed
839
                waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
pixhawk's avatar
pixhawk committed
840
            }
LM's avatar
LM committed
841 842 843 844 845
            else
            {
                qDebug() << "Got waypoint message, but was not for me";
            }
        }
LM's avatar
LM committed
846
            break;
pixhawk's avatar
pixhawk committed
847

lm's avatar
lm committed
848
        case MAVLINK_MSG_ID_MISSION_ITEM:
LM's avatar
LM committed
849 850 851 852 853
        {
            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())
854
            {
LM's avatar
LM committed
855 856 857 858 859
                waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
            }
            else
            {
                qDebug() << "Got waypoint message, but was not for me";
860
            }
LM's avatar
LM committed
861
        }
LM's avatar
LM committed
862
            break;
pixhawk's avatar
pixhawk committed
863

lm's avatar
lm committed
864
        case MAVLINK_MSG_ID_MISSION_ACK:
LM's avatar
LM committed
865 866 867 868
        {
            mavlink_mission_ack_t wpa;
            mavlink_msg_mission_ack_decode(&message, &wpa);
            if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
869
            {
LM's avatar
LM committed
870
                waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
871
            }
LM's avatar
LM committed
872
        }
LM's avatar
LM committed
873
            break;
874

lm's avatar
lm committed
875
        case MAVLINK_MSG_ID_MISSION_REQUEST:
LM's avatar
LM committed
876 877 878 879
        {
            mavlink_mission_request_t wpr;
            mavlink_msg_mission_request_decode(&message, &wpr);
            if(wpr.target_system == mavlink->getSystemId())
880
            {
LM's avatar
LM committed
881
                waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
pixhawk's avatar
pixhawk committed
882
            }
LM's avatar
LM committed
883 884 885
            else
            {
                qDebug() << "Got waypoint message, but was not for me";
pixhawk's avatar
pixhawk committed
886
            }
LM's avatar
LM committed
887
        }
LM's avatar
LM committed
888
            break;
pixhawk's avatar
pixhawk committed
889

lm's avatar
lm committed
890
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
LM's avatar
LM committed
891 892 893 894 895 896 897 898
        {
            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
899
            break;
pixhawk's avatar
pixhawk committed
900

lm's avatar
lm committed
901
        case MAVLINK_MSG_ID_MISSION_CURRENT:
LM's avatar
LM committed
902 903 904 905 906
        {
            mavlink_mission_current_t wpc;
            mavlink_msg_mission_current_decode(&message, &wpc);
            waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
        }
LM's avatar
LM committed
907
            break;
pixhawk's avatar
pixhawk committed
908

909
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
LM's avatar
LM committed
910
        {
911
            if (multiComponentSourceDetected && wrongComponent)
912
            {
913
                break;
LM's avatar
LM committed
914
            }
LM's avatar
LM committed
915 916 917 918
            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
919
            break;
920
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
LM's avatar
LM committed
921 922 923 924 925
        {
            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);
        }
926
            break;
927
        case MAVLINK_MSG_ID_STATUSTEXT:
LM's avatar
LM committed
928 929 930 931 932 933 934 935 936
        {
            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);
937 938 939 940 941 942 943 944 945 946 947

            if (text.startsWith("#audio:"))
            {
                text.remove("#audio:");
                emit textMessageReceived(uasId, message.compid, severity, QString("Audio message: ") + text);
                GAudioOutput::instance()->say(text, severity);
            }
            else
            {
                emit textMessageReceived(uasId, message.compid, severity, text);
            }
LM's avatar
LM committed
948
        }
LM's avatar
LM committed
949
            break;
950
#ifdef MAVLINK_ENABLED_PIXHAWK
951
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
LM's avatar
LM committed
952 953 954 955 956 957 958 959 960 961 962 963 964
        {
            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
965
            break;
966

967
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
LM's avatar
LM committed
968 969 970 971 972
        {
            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
973

LM's avatar
LM committed
974 975 976 977 978 979 980
            // Check if we have a valid transaction
            if (imagePackets == 0)
            {
                // NO VALID TRANSACTION - ABORT
                // Restart statemachine
                imagePacketsArrived = 0;
            }
981

LM's avatar
LM committed
982 983 984 985
            for (int i = 0; i < imagePayload; ++i)
            {
                if (pos <= imageSize) {
                    imageRecBuffer[pos] = img.data[i];
LM's avatar
LM committed
986
                }
LM's avatar
LM committed
987 988
                ++pos;
            }
989

LM's avatar
LM committed
990
            ++imagePacketsArrived;
991

LM's avatar
LM committed
992 993 994 995 996 997
            // emit signal if all packets arrived
            if ((imagePacketsArrived >= imagePackets))
            {
                // Restart statemachine
                imagePacketsArrived = 0;
                emit imageReady(this);
998
                //qDebug() << "imageReady emitted. all packets arrived";
999
            }
LM's avatar
LM committed
1000
        }
LM's avatar
LM committed
1001
            break;
1002
#endif
LM's avatar
LM committed
1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059
            //        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
1060
#ifdef MAVLINK_ENABLED_UALBERTA
1061
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
LM's avatar
LM committed
1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072
        {
            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
1073
            break;
1074
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
LM's avatar
LM committed
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
        {
            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
1102
            break;
1103

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

1135
#if defined(QGC_PROTOBUF_ENABLED)
1136 1137
void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message)
{
LM's avatar
LM committed
1138 1139 1140 1141
    if (!link)
    {
        return;
    }
1142 1143 1144 1145 1146
    if (!links->contains(link))
    {
        addLink(link);
    }

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 1175 1176 1177 1178 1179 1180 1181
    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;
    }

1182
#ifdef QGC_USE_PIXHAWK_MESSAGES
1183
    if (message->GetTypeName() == overlay.GetTypeName())
1184
    {
1185 1186 1187 1188 1189
        receivedOverlayTimestamp = QGC::groundTimeSeconds();
        overlayMutex.lock();
        overlay.CopyFrom(*message);
        overlayMutex.unlock();
        emit overlayChanged(this);
1190
    }
1191 1192
    else if (message->GetTypeName() == obstacleList.GetTypeName())
    {
1193
        receivedObstacleListTimestamp = QGC::groundTimeSeconds();
1194
        obstacleListMutex.lock();
1195
        obstacleList.CopyFrom(*message);
1196
        obstacleListMutex.unlock();
1197 1198
        emit obstacleListChanged(this);
    }
1199 1200
    else if (message->GetTypeName() == path.GetTypeName())
    {
1201
        receivedPathTimestamp = QGC::groundTimeSeconds();
1202
        pathMutex.lock();
1203
        path.CopyFrom(*message);
1204
        pathMutex.unlock();
1205 1206
        emit pathChanged(this);
    }
1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222
    else if (message->GetTypeName() == pointCloud.GetTypeName())
    {
        receivedPointCloudTimestamp = QGC::groundTimeSeconds();
        pointCloudMutex.lock();
        pointCloud.CopyFrom(*message);
        pointCloudMutex.unlock();
        emit pointCloudChanged(this);
    }
    else if (message->GetTypeName() == rgbdImage.GetTypeName())
    {
        receivedRGBDImageTimestamp = QGC::groundTimeSeconds();
        rgbdImageMutex.lock();
        rgbdImage.CopyFrom(*message);
        rgbdImageMutex.unlock();
        emit rgbdImageChanged(this);
    }
1223
#endif
1224 1225 1226 1227
}

#endif

1228 1229
void UAS::setHomePosition(double lat, double lon, double alt)
{
1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258
    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);
    }
1259 1260
}

1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274
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()));


1275 1276
    if (ret == QMessageBox::Yes)
    {
1277 1278 1279 1280
        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);
1281 1282 1283
    }
}

pixhawk's avatar
pixhawk committed
1284 1285
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1286
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1287
    mavlink_message_t msg;
LM's avatar
LM committed
1288
    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
1289
    sendMessage(msg);
1290
#else
lm's avatar
lm committed
1291 1292 1293 1294
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1295
#endif
pixhawk's avatar
pixhawk committed
1296 1297
}

pixhawk's avatar
pixhawk committed
1298 1299
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1300
#ifdef MAVLINK_ENABLED_PIXHAWK
1301
    mavlink_message_t msg;
1302
    mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
1303
    sendMessage(msg);
lm's avatar
lm committed
1304
#else
1305 1306 1307 1308
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1309 1310 1311 1312
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1313
{
1314 1315
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1316
    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);
1317
    sendMessage(msg);
lm's avatar
lm committed
1318 1319
}

1320
void UAS::startDataRecording()
lm's avatar
lm committed
1321
{
1322
    mavlink_message_t msg;
1323
    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);
1324
    sendMessage(msg);
lm's avatar
lm committed
1325 1326 1327 1328
}

void UAS::stopDataRecording()
{
1329
    mavlink_message_t msg;
1330
    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);
1331
    sendMessage(msg);
lm's avatar
lm committed
1332 1333
}

pixhawk's avatar
pixhawk committed
1334 1335
void UAS::startMagnetometerCalibration()
{
1336 1337
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1338
    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);
1339
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1340 1341 1342 1343
}

void UAS::startGyroscopeCalibration()
{
1344 1345
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1346
    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);
1347
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1348 1349 1350 1351
}

void UAS::startPressureCalibration()
{
1352 1353
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1354
    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);
1355
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1356 1357
}

LM's avatar
LM committed
1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384
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
1385
    else if (time < 1261440000000000)
LM's avatar
LM committed
1386
#endif
LM's avatar
LM committed
1387
    {
LM's avatar
LM committed
1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402
        //        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;
    }
}

1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415
/**
 * @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
1416 1417 1418 1419 1420 1421 1422 1423
/**
 * @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!
 */
1424 1425
quint64 UAS::getUnixTime(quint64 time)
{
1426
    quint64 ret = 0;
LM's avatar
LM committed
1427 1428
    if (attitudeStamped)
    {
1429
        ret = lastAttitude;
LM's avatar
LM committed
1430
    }
1431 1432
    if (time == 0)
    {
1433
        ret = QGC::groundTimeMilliseconds();
1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450
    }
    // 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
1451
#ifndef _MSC_VER
1452
    else if (time < 1261440000000000LLU)
1453
#else
LM's avatar
LM committed
1454
    else if (time < 1261440000000000)
1455
#endif
LM's avatar
LM committed
1456
    {
LM's avatar
LM committed
1457
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1458 1459
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1460
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1461
        }
1462
        ret = time/1000 + onboardTimeOffset;
1463 1464 1465
    }
    else
    {
1466 1467
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1468
        ret = time/1000;
1469
    }
1470
    return ret;
1471 1472
}

1473 1474
QList<QString> UAS::getParameterNames(int component)
{
1475 1476
    if (parameters.contains(component))
    {
1477
        return parameters.value(component)->keys();
1478 1479 1480
    }
    else
    {
1481 1482 1483 1484 1485 1486 1487 1488 1489
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1490
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1491
{
LM's avatar
LM committed
1492 1493 1494 1495 1496
    //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
1497 1498 1499 1500 1501
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1502 1503
    foreach (LinkInterface* link, *links)
    {
Lorenz Meier's avatar
Lorenz Meier committed
1504
        qDebug() << "ITERATING THROUGH LINKS";
1505 1506
        if (link)
        {
1507
            sendMessage(link, message);
Lorenz Meier's avatar
Lorenz Meier committed
1508
            qDebug() << "SENT MESSAGE";
1509 1510 1511
        }
        else
        {
1512 1513 1514
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1515 1516 1517
    }
}

1518 1519 1520 1521
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1522

1523 1524 1525 1526
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1527
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1528 1529 1530 1531 1532 1533
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1534
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1535 1536
                        sendMessage(serial, message);
                    }
1537 1538 1539 1540 1541 1542
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1543 1544
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1545
    if(!link) return;
pixhawk's avatar
pixhawk committed
1546 1547 1548
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1549
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1550 1551
    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
1552
    // If link is connected
1553 1554
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1555 1556 1557 1558 1559 1560 1561 1562
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1563
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1564
{
1565
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1566 1567
}

1568 1569
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1570 1571
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
LM's avatar
LM committed
1572 1573 1574 1575 1576 1577 1578 1579
        switch (mode)
        {
        case 0:
            return QString("PREFLIGHT");
            break;
        default:
            return QString("UNKNOWN");
        }
lm's avatar
lm committed
1580 1581 1582 1583 1584 1585 1586 1587 1588
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1589 1590
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1591 1592
}

pixhawk's avatar
pixhawk committed
1593 1594
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1595 1596
    switch (statusCode)
    {
lm's avatar
lm committed
1597
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1598
        uasState = tr("UNINIT");
1599
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1600
        break;
lm's avatar
lm committed
1601
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1602
        uasState = tr("BOOT");
1603
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1604
        break;
lm's avatar
lm committed
1605
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1606
        uasState = tr("CALIBRATING");
1607
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1608
        break;
lm's avatar
lm committed
1609
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1610
        uasState = tr("ACTIVE");
1611
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1612
        break;
lm's avatar
lm committed
1613 1614
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1615
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1616 1617
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1618
        uasState = tr("CRITICAL");
1619
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1620
        break;
lm's avatar
lm committed
1621
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1622
        uasState = tr("EMERGENCY");
1623
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1624
        break;
James Goppert's avatar
James Goppert committed
1625
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1626 1627 1628
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1629

lm's avatar
lm committed
1630
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1631
        uasState = tr("SHUTDOWN");
1632
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1633
        break;
1634

lm's avatar
lm committed
1635
    default:
pixhawk's avatar
pixhawk committed
1636
        uasState = tr("UNKNOWN");
1637
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1638 1639 1640 1641
        break;
    }
}

1642 1643
QImage UAS::getImage()
{
LM's avatar
LM committed
1644 1645
#ifdef MAVLINK_ENABLED_PIXHAWK

1646
//    qDebug() << "IMAGE TYPE:" << imageType;
LM's avatar
LM committed
1647 1648 1649 1650

    // RAW greyscale
    if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
    {
LM's avatar
LM committed
1651 1652
        // TODO FIXME
        int imgColors = 255;//imageSize/(imageWidth*imageHeight);
LM's avatar
LM committed
1653 1654 1655 1656
        //const int headerSize = 15;

        // Construct PGM header
        QString header("P5\n%1 %2\n%3\n");
LM's avatar
LM committed
1657
        header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
LM's avatar
LM committed
1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682

        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
1683
        if (!image.loadFromData(imageRecBuffer))
LM's avatar
LM committed
1684
        {
LM's avatar
LM committed
1685
            qDebug() << "Loading data from image buffer failed!";
LM's avatar
LM committed
1686 1687
        }
    }
1688 1689
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1690
    //imageRecBuffer.clear();
1691
    return image;
1692
#else
LM's avatar
LM committed
1693
    return QImage();
LM's avatar
LM committed
1694
#endif
1695

1696 1697 1698 1699
}

void UAS::requestImage()
{
1700
#ifdef MAVLINK_ENABLED_PIXHAWK
1701 1702
    qDebug() << "trying to get an image from the uas...";

1703 1704 1705
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1706
        mavlink_message_t msg;
LM's avatar
LM committed
1707
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50);
1708 1709
        sendMessage(msg);
    }
1710
#endif
1711
}
pixhawk's avatar
pixhawk committed
1712 1713 1714 1715 1716 1717 1718 1719 1720


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1721
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1722
{
1723 1724
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1725
        return 0;
1726 1727 1728
    }
    else
    {
LM's avatar
LM committed
1729
        return QGC::groundTimeMilliseconds() - startTime;
pixhawk's avatar
pixhawk committed
1730 1731 1732
    }
}

1733
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1734 1735 1736 1737
{
    return commStatus;
}

1738 1739 1740
void UAS::requestParameters()
{
    mavlink_message_t msg;
LM's avatar
LM committed
1741
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
1742
    sendMessage(msg);
Lorenz Meier's avatar
Lorenz Meier committed
1743
    qDebug() << __FILE__ << __LINE__ << "LOADING PARAM LIST";
1744 1745
}

1746
void UAS::writeParametersToStorage()
1747
{
1748
    mavlink_message_t msg;
1749
    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
1750
    qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
1751
    sendMessage(msg);
1752 1753 1754 1755
}

void UAS::readParametersFromStorage()
{
1756
    mavlink_message_t msg;
1757
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
1758
    sendMessage(msg);
lm's avatar
lm committed
1759 1760
}

1761
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1762 1763
{
    // Buffers to write data to
1764
    mavlink_message_t msg;
1765
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1766 1767
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1768
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1769 1770
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1771 1772
    // 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
1773 1774
    stream.req_message_rate = 0;
    // Start / stop the message
1775
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1776 1777 1778 1779 1780
    // 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
1781
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1782 1783
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1784 1785
}

1786
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1787 1788 1789
{
    // Buffers to write data to
    mavlink_message_t msg;
1790
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1791
    // Select the message to request from now on
1792
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1793
    // Select the update rate in Hz the message should be send
1794
    stream.req_message_rate = rate;
lm's avatar
lm committed
1795
    // Start / stop the message
1796
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1797 1798 1799 1800 1801
    // 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
1802
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1803 1804
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1805 1806
}

1807
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1808
{
1809 1810 1811 1812
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1813
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1814
    // Select the update rate in Hz the message should be send
1815
    stream.req_message_rate = rate;
1816
    // Start / stop the message
1817
    stream.start_stop = (rate) ? 1 : 0;
1818 1819 1820 1821 1822 1823
    // 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);
1824 1825
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1826
}
1827

1828
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1829
{
1830 1831 1832 1833 1834
#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
1835 1836 1837
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1838
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1839
    // Select the update rate in Hz the message should be send
1840
    stream.req_message_rate = rate;
1841
    // Start / stop the message
1842
    stream.start_stop = (rate) ? 1 : 0;
1843 1844 1845 1846 1847 1848
    // 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);
1849 1850
    // Send message twice to increase chance of reception
    sendMessage(msg);
1851
#endif
lm's avatar
lm committed
1852 1853
}

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

lm's avatar
lm committed
1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895
//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);
//}
1896

1897
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1898 1899 1900 1901 1902
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1903
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1904
    // Select the update rate in Hz the message should be send
1905
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1906
    // Start / stop the message
1907
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1908 1909 1910 1911 1912 1913 1914 1915 1916 1917
    // 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);
}

1918
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1919 1920 1921 1922 1923
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1924
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1925
    // Select the update rate in Hz the message should be send
1926
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1927
    // Start / stop the message
1928
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939
    // 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);
}

1940
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1941 1942 1943 1944 1945
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1946
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1947
    // Select the update rate in Hz the message should be send
1948
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1949
    // Start / stop the message
1950
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961
    // 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);
}

1962
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1963 1964 1965 1966 1967
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1968
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1969
    // Select the update rate in Hz the message should be send
1970
    stream.req_message_rate = rate;
1971
    // Start / stop the message
1972
    stream.start_stop = (rate) ? 1 : 0;
1973 1974 1975 1976 1977 1978
    // 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);
1979 1980
    // Send message twice to increase chance of reception
    sendMessage(msg);
1981
    sendMessage(msg);
1982 1983
}

lm's avatar
lm committed
1984 1985 1986 1987 1988 1989 1990
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1991
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
lm's avatar
lm committed
1992
{
1993 1994
    if (!id.isNull())
    {
1995 1996
        mavlink_message_t msg;
        mavlink_param_set_t p;
1997 1998 1999 2000 2001 2002 2003
        mavlink_param_union_t union_value;

        // Assign correct value based on QVariant
        switch (value.type())
        {
        case QVariant::Int:
            union_value.param_int32 = value.toInt();
2004
            p.param_type = MAVLINK_TYPE_INT32_T;
2005 2006 2007
            break;
        case QVariant::UInt:
            union_value.param_uint32 = value.toUInt();
2008
            p.param_type = MAVLINK_TYPE_UINT32_T;
2009 2010 2011
            break;
        case QMetaType::Float:
            union_value.param_float = value.toFloat();
2012
            p.param_type = MAVLINK_TYPE_FLOAT;
2013 2014 2015 2016 2017 2018 2019
            break;
        default:
            qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
            return;
        }

        p.param_value = union_value.param_float;
2020 2021 2022
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

2023 2024
        qDebug() << "SENT PARAM:" << value;

2025
        // Copy string into buffer, ensuring not to exceed the buffer size
2026 2027
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
2028
            // String characters
2029 2030
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
2031 2032
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
2033 2034 2035 2036 2037
            //        // 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';
            //        }
2038
            // Zero fill
2039 2040
            else
            {
2041 2042
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
2043
        }
2044 2045
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
2046
    }
2047 2048
}

2049 2050 2051 2052 2053 2054 2055 2056 2057 2058 2059 2060 2061 2062
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;
}

2063
void UAS::requestParameter(int component, const QString& parameter)
2064
{
2065
    // Request parameter, use parameter name to request it
2066 2067
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
2068 2069 2070 2071 2072 2073 2074 2075
    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
2076 2077 2078 2079
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
2080
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
2081 2082
}

2083 2084
void UAS::setSystemType(int systemType)
{
2085
    if((systemType >= MAV_TYPE_GENERIC) && (systemType < MAV_TYPE_ENUM_END))
2086
    {
2087 2088 2089 2090 2091 2092 2093 2094 2095 2096 2097 2098 2099 2100 2101 2102 2103
      type = systemType;
    
      // If the airframe is still generic, change it to a close default type
      if (airframe == 0)
      {
          switch (systemType)
          {
          case MAV_TYPE_FIXED_WING:
              airframe = QGC_AIRFRAME_EASYSTAR;
              break;
          case MAV_TYPE_QUADROTOR:
              airframe = QGC_AIRFRAME_MIKROKOPTER;
              break;
          }
      }
      emit systemSpecsChanged(uasId);
   }
2104 2105
}

2106 2107
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
2108 2109 2110 2111 2112 2113 2114
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
2115 2116
}

lm's avatar
lm committed
2117 2118 2119
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
2120
    mavlink_command_long_t cmd;
LM's avatar
LM committed
2121
    cmd.command = (uint16_t)command;
2122 2123 2124 2125 2126
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
2127 2128 2129
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
2130 2131
    cmd.target_system = uasId;
    cmd.target_component = 0;
2132
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
2133 2134 2135
    sendMessage(msg);
}

2136 2137 2138 2139
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;
LM's avatar
LM committed
2140
    cmd.command = (uint16_t)command;
2141 2142 2143 2144 2145
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
2146 2147 2148
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
2149 2150
    cmd.target_system = uasId;
    cmd.target_component = component;
2151
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
2152 2153 2154
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
2155
/**
lm's avatar
lm committed
2156
 * Launches the system
pixhawk's avatar
pixhawk committed
2157 2158 2159 2160
 *
 **/
void UAS::launch()
{
2161
    mavlink_message_t msg;
2162
    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);
2163
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2164 2165 2166 2167 2168 2169
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
2170
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
2171
{
2172
    mavlink_message_t msg;
2173
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
2174
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2175 2176 2177 2178 2179 2180
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
2181
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
2182
{
2183
    mavlink_message_t msg;
2184
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
2185
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2186 2187 2188 2189 2190 2191 2192 2193 2194 2195 2196 2197 2198 2199
}

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
2200 2201
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
2202
    {
2203 2204 2205 2206
        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
2207

LM's avatar
LM committed
2208
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
2209 2210 2211
    }
    else
    {
2212 2213
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2214 2215
}

2216 2217 2218 2219 2220
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2221 2222
void UAS::receiveButton(int buttonIndex)
{
2223 2224
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2225
    case 0:
pixhawk's avatar
pixhawk committed
2226

pixhawk's avatar
pixhawk committed
2227 2228
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2229

pixhawk's avatar
pixhawk committed
2230 2231 2232 2233 2234
        break;
    default:

        break;
    }
2235
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2236 2237 2238

}

2239

pixhawk's avatar
pixhawk committed
2240 2241
void UAS::halt()
{
2242 2243 2244
    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
2245 2246 2247 2248
}

void UAS::go()
{
2249 2250 2251
    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
2252 2253
}

2254
/** Order the robot to return home **/
pixhawk's avatar
pixhawk committed
2255 2256
void UAS::home()
{
2257 2258 2259 2260 2261 2262 2263 2264 2265
    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
2266 2267
}

2268 2269 2270 2271 2272 2273 2274 2275 2276
/** Order the robot to land on the runway **/
void UAS::land()
{
    mavlink_message_t msg;

    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_LAND, 1, 0, 0, 0, 0, 0, 0, 0);
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
2277 2278 2279 2280 2281 2282
/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2283 2284
    // FIXME MAVLINKV10PORTINGNEEDED
    halt();
pixhawk's avatar
pixhawk committed
2285 2286 2287
}

/**
lm's avatar
lm committed
2288
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2289 2290 2291 2292 2293 2294
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
2295
    halt();
lm's avatar
lm committed
2296
    // FIXME MAVLINKV10PORTINGNEEDED
LM's avatar
LM committed
2297 2298 2299 2300 2301 2302 2303 2304 2305 2306 2307 2308 2309 2310 2311 2312 2313 2314 2315 2316 2317 2318 2319 2320
    //    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
2321
    return false;
pixhawk's avatar
pixhawk committed
2322 2323
}

lm's avatar
lm committed
2324 2325 2326 2327 2328
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2329
        startHil();
lm's avatar
lm committed
2330 2331 2332
    }
    else
    {
2333
        stopHil();
lm's avatar
lm committed
2334 2335 2336 2337 2338 2339 2340 2341 2342 2343 2344 2345 2346 2347 2348 2349 2350 2351 2352 2353 2354 2355
    }
}

/**
* @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
2356 2357
                       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
2358 2359 2360 2361 2362 2363 2364
{
    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);
}


2365 2366
void UAS::startHil()
{
lm's avatar
lm committed
2367 2368
    // Connect Flight Gear Link
    simulation->connectSimulation();
2369
    mavlink_message_t msg;
LM's avatar
LM committed
2370
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
2371
    sendMessage(msg);
2372 2373
}

2374 2375
void UAS::stopHil()
{
lm's avatar
lm committed
2376
    simulation->disconnectSimulation();
2377
    mavlink_message_t msg;
LM's avatar
LM committed
2378
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
2379
    sendMessage(msg);
2380 2381 2382
}


pixhawk's avatar
pixhawk committed
2383 2384
void UAS::shutdown()
{
2385 2386 2387 2388 2389
    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
2390

2391 2392 2393
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2394

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

2398 2399 2400 2401
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2402
        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);
2403 2404 2405
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2406 2407
}

2408 2409
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2410
    mavlink_message_t msg;
2411
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 1, 1, 0, yaw, x, y, z);
2412
    sendMessage(msg);
2413 2414
}

pixhawk's avatar
pixhawk committed
2415 2416 2417
/**
 * @return The name of this system as string in human-readable form
 */
2418
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2419 2420
{
    QString result;
2421 2422
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2423
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2424 2425 2426
    }
    else
    {
pixhawk's avatar
pixhawk committed
2427 2428 2429 2430 2431
        result = name;
    }
    return result;
}

2432 2433 2434 2435 2436
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2437 2438 2439 2440 2441 2442 2443 2444 2445 2446 2447 2448 2449 2450 2451 2452 2453 2454 2455 2456 2457 2458 2459 2460 2461 2462 2463 2464 2465 2466 2467 2468 2469 2470 2471 2472 2473 2474 2475
QString UAS::getAudioModeTextFor(int id)
{
    QString mode;
    uint8_t modeid = id;

    // BASE MODE DECODING
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
    {
        mode += "autonomous";
    }
    else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
    {
        mode += "guided";
    }
    else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
    {
        mode += "manual";
    }

    if (modeid != 0)
    {
        mode += " mode";
    }

    // ARMED STATE DECODING
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
    {
        mode.append(" and armed");
    }

    // HARDWARE IN THE LOOP DECODING
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
    {
        mode.append(" using hardware in the loop simulation");
    }

    return mode;
}

2476 2477 2478
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2479 2480 2481
    uint8_t modeid = id;

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

LM's avatar
LM committed
2483
    // BASE MODE DECODING
pixhawk's avatar
pixhawk committed
2484
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
LM's avatar
LM committed
2485
    {
pixhawk's avatar
pixhawk committed
2486
        mode += "AUTO";
LM's avatar
LM committed
2487
    }
pixhawk's avatar
pixhawk committed
2488
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
LM's avatar
LM committed
2489
    {
LM's avatar
LM committed
2490
        mode += "|GUID";
LM's avatar
LM committed
2491
    }
pixhawk's avatar
pixhawk committed
2492
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
LM's avatar
LM committed
2493
    {
LM's avatar
LM committed
2494
        mode += "|STAB";
LM's avatar
LM committed
2495
    }
pixhawk's avatar
pixhawk committed
2496
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
LM's avatar
LM committed
2497
    {
LM's avatar
LM committed
2498
        mode += "|TEST";
LM's avatar
LM committed
2499
    }
pixhawk's avatar
pixhawk committed
2500
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
LM's avatar
LM committed
2501
    {
LM's avatar
LM committed
2502
        mode += "|MAN";
LM's avatar
LM committed
2503
    }
pixhawk's avatar
pixhawk committed
2504 2505

    if (modeid == 0)
LM's avatar
LM committed
2506
    {
2507
        mode = "PREFLIGHT";
LM's avatar
LM committed
2508 2509 2510
    }

    // ARMED STATE DECODING
pixhawk's avatar
pixhawk committed
2511
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
LM's avatar
LM committed
2512
    {
LM's avatar
LM committed
2513
        mode.prepend("A/");
LM's avatar
LM committed
2514 2515 2516
    }
    else
    {
LM's avatar
LM committed
2517
        mode.prepend("D/");
LM's avatar
LM committed
2518 2519 2520
    }

    // HARDWARE IN THE LOOP DECODING
pixhawk's avatar
pixhawk committed
2521
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
LM's avatar
LM committed
2522 2523
    {
        mode.prepend("HIL:");
2524 2525 2526 2527 2528
    }

    return mode;
}

2529 2530 2531 2532 2533
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2534 2535
void UAS::addLink(LinkInterface* link)
{
2536 2537
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2538
        links->append(link);
2539
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2540 2541 2542
    }
}

2543 2544 2545
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2546 2547
    if (link)
    {
2548 2549 2550 2551
        links->removeAt(links->indexOf(link));
    }
}

LM's avatar
LM committed
2552

pixhawk's avatar
pixhawk committed
2553 2554 2555 2556 2557
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}

LM's avatar
LM committed
2558 2559 2560 2561 2562
QMap<int, QString> UAS::getComponents()
{
    return components;
}

pixhawk's avatar
pixhawk committed
2563 2564 2565 2566 2567 2568


void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2569 2570
    switch (batteryType)
    {
lm's avatar
lm committed
2571
    case NICD:
pixhawk's avatar
pixhawk committed
2572
        break;
lm's avatar
lm committed
2573
    case NIMH:
pixhawk's avatar
pixhawk committed
2574
        break;
lm's avatar
lm committed
2575
    case LIION:
pixhawk's avatar
pixhawk committed
2576
        break;
lm's avatar
lm committed
2577
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2578 2579 2580
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2581
    case LIFE:
pixhawk's avatar
pixhawk committed
2582
        break;
lm's avatar
lm committed
2583
    case AGZN:
pixhawk's avatar
pixhawk committed
2584 2585 2586 2587
        break;
    }
}

2588 2589
void UAS::setBatterySpecs(const QString& specs)
{
2590 2591
    if (specs.length() == 0 || specs.contains("%"))
    {
2592
        batteryRemainingEstimateEnabled = false;
2593
        bool ok;
2594 2595 2596
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2597 2598
        if (ok)
        {
2599
            warnLevelPercent = temp;
2600 2601 2602
        }
        else
        {
2603 2604
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2605 2606 2607
    }
    else
    {
2608 2609 2610 2611 2612
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2613 2614
        if (parts.length() == 3)
        {
2615 2616 2617 2618 2619 2620 2621 2622 2623 2624 2625
            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;
2626 2627 2628
        }
        else
        {
2629 2630
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2631 2632 2633 2634 2635
    }
}

QString UAS::getBatterySpecs()
{
2636 2637
    if (batteryRemainingEstimateEnabled)
    {
2638
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2639 2640 2641
    }
    else
    {
2642 2643
        return QString("%1%").arg(warnLevelPercent);
    }
2644 2645
}

pixhawk's avatar
pixhawk committed
2646 2647
int UAS::calculateTimeRemaining()
{
LM's avatar
LM committed
2648
    quint64 dt = QGC::groundTimeMilliseconds() - startTime;
pixhawk's avatar
pixhawk committed
2649 2650 2651 2652 2653 2654 2655 2656 2657 2658
    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
2659 2660 2661
/**
 * @return charge level in percent - 0 - 100
 */
2662
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2663
{
2664 2665 2666 2667
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2668
            chargeLevel = 0.0f;
2669 2670 2671
        }
        else if (lpVoltage > fullVoltage)
        {
2672
            chargeLevel = 100.0f;
2673 2674 2675
        }
        else
        {
2676 2677
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2678 2679
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2680 2681
}

lm's avatar
lm committed
2682 2683
void UAS::startLowBattAlarm()
{
2684 2685
    if (!lowBattAlarm)
    {
2686
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2687
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2688 2689 2690 2691 2692 2693
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2694 2695
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2696 2697 2698 2699
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}