UAS.cc 91.6 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 89 90 91 92 93 94 95 96
    paramsOnceRequested(false),
    airframe(QGC_AIRFRAME_EASYSTAR),
    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)
pixhawk's avatar
pixhawk committed
100
{
101 102 103 104 105 106
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
    }

107
    color = UASInterface::getNextColor();
lm's avatar
lm committed
108
    setBatterySpecs(QString("9V,9.5V,12.6V"));
109
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
110
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
111
    statusTimeout->start(500);
112
    readSettings();
113 114 115 116

    // Initial signals
    emit disarmed();
    emit armingChanged(false);
pixhawk's avatar
pixhawk committed
117 118 119 120
}

UAS::~UAS()
{
121
    writeSettings();
pixhawk's avatar
pixhawk committed
122
    delete links;
123
    links=NULL;
pixhawk's avatar
pixhawk committed
124 125
}

126 127 128 129 130
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
131 132
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
133
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
134 135 136 137 138 139 140 141 142
    settings.endGroup();
    settings.sync();
}

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

152
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
153 154 155 156
{
    return uasId;
}

157 158
void UAS::updateState()
{
159 160
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
161 162
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
163 164 165 166
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

167 168
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
169 170
    if (positionLock)
    {
171
        positionLock = false;
172 173 174
    }
    else
    {
lm's avatar
lm committed
175
        if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock)
176
        {
177 178 179 180 181
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
182 183
void UAS::setSelected()
{
184 185
    if (UASManager::instance()->getActiveUAS() != this)
    {
186 187 188 189 190 191 192 193
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

bool UAS::getSelected() const
{
    return (UASManager::instance()->getActiveUAS() == this);
pixhawk's avatar
pixhawk committed
194 195 196 197
}

void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
198
    if (!link) return;
199 200
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
201
        addLink(link);
202
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
203 204
    }

LM's avatar
LM committed
205 206 207 208 209 210 211
    if (!components.contains(message.compid))
    {
        QString componentName;

        switch (message.compid)
        {
        case MAV_COMP_ID_ALL:
LM's avatar
LM committed
212 213 214 215
        {
            componentName = "ANONYMOUS";
            break;
        }
LM's avatar
LM committed
216
        case MAV_COMP_ID_IMU:
LM's avatar
LM committed
217 218 219 220
        {
            componentName = "IMU #1";
            break;
        }
LM's avatar
LM committed
221
        case MAV_COMP_ID_CAMERA:
LM's avatar
LM committed
222 223 224 225
        {
            componentName = "CAMERA";
            break;
        }
LM's avatar
LM committed
226
        case MAV_COMP_ID_MISSIONPLANNER:
LM's avatar
LM committed
227 228 229 230
        {
            componentName = "MISSIONPLANNER";
            break;
        }
LM's avatar
LM committed
231 232 233 234 235 236
        }

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

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

LM's avatar
LM committed
239 240 241 242
    // 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))
243
    {
pixhawk's avatar
pixhawk committed
244 245
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
246

247 248 249
        bool multiComponentSourceDetected = false;
        bool wrongComponent = false;

250 251 252 253 254 255 256 257 258 259 260
        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;
        }

261 262 263
        // Store component ID
        if (componentID[message.msgid] == -1)
        {
264
            // Prefer the first component
265 266 267 268 269 270 271 272 273 274 275 276 277 278 279
            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;


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

327 328 329 330 331 332 333 334 335 336 337 338 339 340 341
            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();
                }
            }
342

343
            QString audiostring = QString("System %1").arg(uasId);
344 345 346 347 348
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
349

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

352 353

            if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT)
354 355 356 357 358 359
            {
                statechanged = true;
                this->status = state.system_status;
                getStatusForCode((int)state.system_status, uasState, stateDescription);
                emit statusChanged(this, uasState, stateDescription);
                emit statusChanged(this->status);
360

361
                shortStateText = uasState;
362

363 364
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
365

366
            if (this->mode != static_cast<int>(state.base_mode))
367 368
            {
                modechanged = true;
369
                this->mode = static_cast<int>(state.base_mode);
370
                shortModeText = getShortModeTextFor(this->mode);
371

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

374
                modeAudio = " is now in " + audiomodeText;
375
            }
LM's avatar
LM committed
376

377
            if (navMode != state.custom_mode)
378
            {
379 380
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
LM's avatar
LM committed
381
                //navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
382
            }
383

384 385 386 387 388 389 390 391 392 393 394
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
395

396 397 398 399 400 401 402
            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();
403
                GAudioOutput::instance()->say(audiostring.toLower());
404
            }
LM's avatar
LM committed
405
        }
406

407 408 409
            break;
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
LM's avatar
LM committed
410 411 412 413 414 415
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_sys_status_t state;
            mavlink_msg_sys_status_decode(&message, &state);
416

417 418 419 420 421 422 423 424 425
			// 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);
426
            emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);
427 428

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

432
			// Battery charge/time remaining/voltage calculations
LM's avatar
LM committed
433 434
            currentVoltage = state.voltage_battery/1000.0f;
            lpVoltage = filterVoltage(currentVoltage);
435
            tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage;
LM's avatar
LM committed
436

437 438 439 440 441 442 443 444 445
            // 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))
            {
446
                GAudioOutput::instance()->say(QString("voltage warning: %1 volt").arg(lpVoltage, 0, 'f', 1, QChar(' ')));
447 448 449 450
                lastTickVoltageValue = tickLowpassVoltage;
            }

            if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage;
LM's avatar
LM committed
451 452 453 454 455 456
            timeRemaining = calculateTimeRemaining();
            if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
            {
                chargeLevel = state.battery_remaining;
            }
            emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
457 458 459 460 461 462 463 464 465
			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);
			}
466

LM's avatar
LM committed
467
            // LOW BATTERY ALARM
468
            if (lpVoltage < warnVoltage && (startVoltage > 0.0f))
LM's avatar
LM committed
469 470
            {
                startLowBattAlarm();
471
            }
LM's avatar
LM committed
472
            else
LM's avatar
LM committed
473
            {
LM's avatar
LM committed
474
                stopLowBattAlarm();
pixhawk's avatar
pixhawk committed
475
            }
476

477 478 479 480 481 482 483
            // 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));

484 485 486 487 488 489
			// 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)
			{
490
				state.drop_rate_comm = 10000;
491
			}
492 493
			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);
494
		}
LM's avatar
LM committed
495
            break;
pixhawk's avatar
pixhawk committed
496
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
497 498 499 500
        {
            mavlink_attitude_t attitude;
            mavlink_msg_attitude_decode(&message, &attitude);
            quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531

            emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time);

            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
532
        }
LM's avatar
LM committed
533
            break;
534 535 536 537 538 539 540 541 542 543 544 545
        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
546
        case MAVLINK_MSG_ID_HIL_CONTROLS:
LM's avatar
LM committed
547 548 549 550 551
        {
            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
552
            break;
553
        case MAVLINK_MSG_ID_VFR_HUD:
LM's avatar
LM committed
554 555 556 557 558 559
        {
            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
560

LM's avatar
LM committed
561 562 563 564
            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
565
            }
LM's avatar
LM committed
566 567 568 569

            emit altitudeChanged(uasId, hud.alt);
            emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
        }
LM's avatar
LM committed
570
            break;
lm's avatar
lm committed
571
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
lm's avatar
lm committed
572
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
573
            //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
574 575 576 577
        {
            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
578

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

LM's avatar
LM committed
582

LM's avatar
LM committed
583 584 585 586 587
            if (!wrongComponent)
            {
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
588

LM's avatar
LM committed
589
                // Emit
590

LM's avatar
LM committed
591 592
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
593

LM's avatar
LM committed
594 595 596 597
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
LM's avatar
LM committed
598
                }
LM's avatar
LM committed
599 600
                positionLock = true;
                isLocalPositionKnown = true;
601
            }
LM's avatar
LM committed
602
        }
603 604
            break;
        case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
LM's avatar
LM committed
605 606 607 608 609 610 611
        {
            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
612
            break;
613
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
614 615
            //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
616 617 618 619 620 621 622 623 624 625 626 627
        {
            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);
628

LM's avatar
LM committed
629 630
            // Set internal state
            if (!positionLock)
LM's avatar
LM committed
631
            {
LM's avatar
LM committed
632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649
                // 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);
650 651 652 653 654 655 656 657 658
            
            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
659 660

            if (pos.fix_type > 2)
LM's avatar
LM committed
661
            {
LM's avatar
LM committed
662
                emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
LM's avatar
LM committed
663 664 665 666
                latitude = pos.lat/(double)1E7;
                longitude = pos.lon/(double)1E7;
                altitude = pos.alt/1000.0;
                positionLock = true;
667
                isGlobalPositionKnown = true;
LM's avatar
LM committed
668

LM's avatar
LM committed
669 670 671
                // Check for NaN
                int alt = pos.alt;
                if (!isnan(alt) && !isinf(alt))
672
                {
LM's avatar
LM committed
673 674 675 676 677
                    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
678

LM's avatar
LM committed
679
                float vel = pos.vel/100.0f;
LM's avatar
LM committed
680

LM's avatar
LM committed
681 682 683 684 685 686 687 688 689
                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
690 691
                }
            }
LM's avatar
LM committed
692
        }
LM's avatar
LM committed
693
            break;
694
        case MAVLINK_MSG_ID_GPS_STATUS:
LM's avatar
LM committed
695 696 697 698
        {
            mavlink_gps_status_t pos;
            mavlink_msg_gps_status_decode(&message, &pos);
            for(int i = 0; i < (int)pos.satellites_visible; i++)
699
            {
LM's avatar
LM committed
700
                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]));
701
            }
LM's avatar
LM committed
702
        }
LM's avatar
LM committed
703
            break;
704
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
LM's avatar
LM committed
705 706 707
        {
            mavlink_gps_global_origin_t pos;
            mavlink_msg_gps_global_origin_decode(&message, &pos);
708
            emit homePositionChanged(uasId, pos.latitude / 10000000.0, pos.longitude / 10000000.0, pos.altitude / 1000.0);
LM's avatar
LM committed
709
        }
LM's avatar
LM committed
710
            break;
711
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
LM's avatar
LM committed
712 713 714 715 716 717 718 719 720 721 722 723 724
        {
            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
725
            break;
726
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
LM's avatar
LM committed
727 728 729 730 731 732 733 734 735 736 737 738 739
        {
            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
740
            break;
741
        case MAVLINK_MSG_ID_PARAM_VALUE:
LM's avatar
LM committed
742 743 744 745 746 747 748 749 750 751 752 753
        {
            mavlink_param_value_t value;
            mavlink_msg_param_value_decode(&message, &value);
            QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
            QString parameterName = QString(bytes);
            int component = message.compid;
            mavlink_param_union_t val;
            val.param_float = value.param_value;
            val.type = value.param_type;

            // Insert component if necessary
            if (!parameters.contains(component))
754
            {
LM's avatar
LM committed
755 756
                parameters.insert(component, new QMap<QString, QVariant>());
            }
757

LM's avatar
LM committed
758 759
            // Insert parameter into registry
            if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
760

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

lm's avatar
lm committed
837
        case MAVLINK_MSG_ID_MISSION_ITEM:
LM's avatar
LM committed
838 839 840 841 842
        {
            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())
843
            {
LM's avatar
LM committed
844 845 846 847 848
                waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
            }
            else
            {
                qDebug() << "Got waypoint message, but was not for me";
849
            }
LM's avatar
LM committed
850
        }
LM's avatar
LM committed
851
            break;
pixhawk's avatar
pixhawk committed
852

lm's avatar
lm committed
853
        case MAVLINK_MSG_ID_MISSION_ACK:
LM's avatar
LM committed
854 855 856 857
        {
            mavlink_mission_ack_t wpa;
            mavlink_msg_mission_ack_decode(&message, &wpa);
            if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
858
            {
LM's avatar
LM committed
859
                waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
860
            }
LM's avatar
LM committed
861
        }
LM's avatar
LM committed
862
            break;
863

lm's avatar
lm committed
864
        case MAVLINK_MSG_ID_MISSION_REQUEST:
LM's avatar
LM committed
865 866 867 868
        {
            mavlink_mission_request_t wpr;
            mavlink_msg_mission_request_decode(&message, &wpr);
            if(wpr.target_system == mavlink->getSystemId())
869
            {
LM's avatar
LM committed
870
                waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
pixhawk's avatar
pixhawk committed
871
            }
LM's avatar
LM committed
872 873 874
            else
            {
                qDebug() << "Got waypoint message, but was not for me";
pixhawk's avatar
pixhawk committed
875
            }
LM's avatar
LM committed
876
        }
LM's avatar
LM committed
877
            break;
pixhawk's avatar
pixhawk committed
878

lm's avatar
lm committed
879
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
LM's avatar
LM committed
880 881 882 883 884 885 886 887
        {
            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
888
            break;
pixhawk's avatar
pixhawk committed
889

lm's avatar
lm committed
890
        case MAVLINK_MSG_ID_MISSION_CURRENT:
LM's avatar
LM committed
891 892 893 894 895
        {
            mavlink_mission_current_t wpc;
            mavlink_msg_mission_current_decode(&message, &wpc);
            waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
        }
LM's avatar
LM committed
896
            break;
pixhawk's avatar
pixhawk committed
897

898
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
LM's avatar
LM committed
899
        {
900
            if (multiComponentSourceDetected && wrongComponent)
901
            {
902
                break;
LM's avatar
LM committed
903
            }
LM's avatar
LM committed
904 905 906 907
            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
908
            break;
909
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
LM's avatar
LM committed
910 911 912 913 914
        {
            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);
        }
915
            break;
916
        case MAVLINK_MSG_ID_STATUSTEXT:
LM's avatar
LM committed
917 918 919 920 921 922 923 924 925
        {
            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);
926 927 928 929 930 931 932 933 934 935 936

            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
937
        }
LM's avatar
LM committed
938
            break;
939
#ifdef MAVLINK_ENABLED_PIXHAWK
940
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
LM's avatar
LM committed
941 942 943 944 945 946 947 948 949 950 951 952 953
        {
            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
954
            break;
955

956
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
LM's avatar
LM committed
957 958 959 960 961
        {
            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
962

LM's avatar
LM committed
963 964 965 966 967 968 969
            // Check if we have a valid transaction
            if (imagePackets == 0)
            {
                // NO VALID TRANSACTION - ABORT
                // Restart statemachine
                imagePacketsArrived = 0;
            }
970

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

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

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

1093
#endif
LM's avatar
LM committed
1094
            // Messages to ignore
lm's avatar
lm committed
1095 1096 1097 1098 1099 1100 1101 1102
        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
1103
        case MAVLINK_MSG_ID_DEBUG:
1104 1105
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
1106
            break;
1107
        default:
LM's avatar
LM committed
1108 1109
        {
            if (!unknownPackets.contains(message.msgid))
1110
            {
LM's avatar
LM committed
1111 1112
                unknownPackets.append(message.msgid);
                QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid);
1113
                //GAudioOutput::instance()->say(errString+tr(", please check console for details."));
LM's avatar
LM committed
1114 1115 1116
                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
1117
            }
LM's avatar
LM committed
1118
        }
LM's avatar
LM committed
1119
            break;
pixhawk's avatar
pixhawk committed
1120 1121 1122 1123
        }
    }
}

1124
#if defined(QGC_PROTOBUF_ENABLED)
1125 1126
void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message)
{
LM's avatar
LM committed
1127 1128 1129 1130
    if (!link)
    {
        return;
    }
1131 1132 1133 1134 1135
    if (!links->contains(link))
    {
        addLink(link);
    }

1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170
    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;
    }

1171
#ifdef QGC_USE_PIXHAWK_MESSAGES
1172
    if (message->GetTypeName() == overlay.GetTypeName())
1173
    {
1174 1175 1176 1177 1178
        receivedOverlayTimestamp = QGC::groundTimeSeconds();
        overlayMutex.lock();
        overlay.CopyFrom(*message);
        overlayMutex.unlock();
        emit overlayChanged(this);
1179
    }
1180 1181
    else if (message->GetTypeName() == obstacleList.GetTypeName())
    {
1182
        receivedObstacleListTimestamp = QGC::groundTimeSeconds();
1183
        obstacleListMutex.lock();
1184
        obstacleList.CopyFrom(*message);
1185
        obstacleListMutex.unlock();
1186 1187
        emit obstacleListChanged(this);
    }
1188 1189
    else if (message->GetTypeName() == path.GetTypeName())
    {
1190
        receivedPathTimestamp = QGC::groundTimeSeconds();
1191
        pathMutex.lock();
1192
        path.CopyFrom(*message);
1193
        pathMutex.unlock();
1194 1195
        emit pathChanged(this);
    }
1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211
    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);
    }
1212
#endif
1213 1214 1215 1216
}

#endif

1217 1218
void UAS::setHomePosition(double lat, double lon, double alt)
{
1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247
    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);
    }
1248 1249
}

1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263
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()));


1264 1265
    if (ret == QMessageBox::Yes)
    {
1266 1267 1268 1269
        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);
1270 1271 1272
    }
}

pixhawk's avatar
pixhawk committed
1273 1274
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1275
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1276
    mavlink_message_t msg;
LM's avatar
LM committed
1277
    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
1278
    sendMessage(msg);
1279
#else
lm's avatar
lm committed
1280 1281 1282 1283
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1284
#endif
pixhawk's avatar
pixhawk committed
1285 1286
}

pixhawk's avatar
pixhawk committed
1287 1288
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1289
#ifdef MAVLINK_ENABLED_PIXHAWK
1290
    mavlink_message_t msg;
1291
    mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
1292
    sendMessage(msg);
lm's avatar
lm committed
1293
#else
1294 1295 1296 1297
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1298 1299 1300 1301
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1302
{
1303 1304
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1305
    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);
1306
    sendMessage(msg);
lm's avatar
lm committed
1307 1308
}

1309
void UAS::startDataRecording()
lm's avatar
lm committed
1310
{
1311
    mavlink_message_t msg;
1312
    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);
1313
    sendMessage(msg);
lm's avatar
lm committed
1314 1315 1316 1317
}

void UAS::stopDataRecording()
{
1318
    mavlink_message_t msg;
1319
    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);
1320
    sendMessage(msg);
lm's avatar
lm committed
1321 1322
}

pixhawk's avatar
pixhawk committed
1323 1324
void UAS::startMagnetometerCalibration()
{
1325 1326
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1327
    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);
1328
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1329 1330 1331 1332
}

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

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

LM's avatar
LM committed
1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373
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
1374
    else if (time < 1261440000000000)
LM's avatar
LM committed
1375
#endif
LM's avatar
LM committed
1376
    {
LM's avatar
LM committed
1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391
        //        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;
    }
}

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

1462 1463
QList<QString> UAS::getParameterNames(int component)
{
1464 1465
    if (parameters.contains(component))
    {
1466
        return parameters.value(component)->keys();
1467 1468 1469
    }
    else
    {
1470 1471 1472 1473 1474 1475 1476 1477 1478
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1479
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1480
{
LM's avatar
LM committed
1481 1482 1483 1484 1485
    //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
1486 1487 1488 1489 1490
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1491 1492
    foreach (LinkInterface* link, *links)
    {
Lorenz Meier's avatar
Lorenz Meier committed
1493
        qDebug() << "ITERATING THROUGH LINKS";
1494 1495
        if (link)
        {
1496
            sendMessage(link, message);
Lorenz Meier's avatar
Lorenz Meier committed
1497
            qDebug() << "SENT MESSAGE";
1498 1499 1500
        }
        else
        {
1501 1502 1503
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1504 1505 1506
    }
}

1507 1508 1509 1510
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1511

1512 1513 1514 1515
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1516
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1517 1518 1519 1520 1521 1522
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1523
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1524 1525
                        sendMessage(serial, message);
                    }
1526 1527 1528 1529 1530 1531
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1532 1533
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1534
    if(!link) return;
pixhawk's avatar
pixhawk committed
1535 1536 1537
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1538
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1539 1540
    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
1541
    // If link is connected
1542 1543
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1544 1545 1546 1547 1548 1549 1550 1551
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1552
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1553
{
1554
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1555 1556
}

1557 1558
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1559 1560
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
LM's avatar
LM committed
1561 1562 1563 1564 1565 1566 1567 1568
        switch (mode)
        {
        case 0:
            return QString("PREFLIGHT");
            break;
        default:
            return QString("UNKNOWN");
        }
lm's avatar
lm committed
1569 1570 1571 1572 1573 1574 1575 1576 1577
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1578 1579
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1580 1581
}

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

lm's avatar
lm committed
1619
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1620
        uasState = tr("SHUTDOWN");
1621
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1622
        break;
1623

lm's avatar
lm committed
1624
    default:
pixhawk's avatar
pixhawk committed
1625
        uasState = tr("UNKNOWN");
1626
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1627 1628 1629 1630
        break;
    }
}

1631 1632
QImage UAS::getImage()
{
LM's avatar
LM committed
1633 1634 1635 1636 1637 1638 1639
#ifdef MAVLINK_ENABLED_PIXHAWK

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

    // RAW greyscale
    if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
    {
LM's avatar
LM committed
1640 1641
        // TODO FIXME
        int imgColors = 255;//imageSize/(imageWidth*imageHeight);
LM's avatar
LM committed
1642 1643 1644 1645
        //const int headerSize = 15;

        // Construct PGM header
        QString header("P5\n%1 %2\n%3\n");
LM's avatar
LM committed
1646
        header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
LM's avatar
LM committed
1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671

        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
1672
        if (!image.loadFromData(imageRecBuffer))
LM's avatar
LM committed
1673
        {
LM's avatar
LM committed
1674
            qDebug() << "Loading data from image buffer failed!";
LM's avatar
LM committed
1675 1676
        }
    }
1677 1678
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1679
    //imageRecBuffer.clear();
1680
    return image;
1681
#else
LM's avatar
LM committed
1682
    return QImage();
LM's avatar
LM committed
1683
#endif
1684

1685 1686 1687 1688
}

void UAS::requestImage()
{
1689
#ifdef MAVLINK_ENABLED_PIXHAWK
1690 1691
    qDebug() << "trying to get an image from the uas...";

1692 1693 1694
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1695
        mavlink_message_t msg;
LM's avatar
LM committed
1696
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50);
1697 1698
        sendMessage(msg);
    }
1699
#endif
1700
}
pixhawk's avatar
pixhawk committed
1701 1702 1703 1704 1705 1706 1707 1708 1709


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1710
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1711
{
1712 1713
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1714
        return 0;
1715 1716 1717
    }
    else
    {
LM's avatar
LM committed
1718
        return QGC::groundTimeMilliseconds() - startTime;
pixhawk's avatar
pixhawk committed
1719 1720 1721
    }
}

1722
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1723 1724 1725 1726
{
    return commStatus;
}

1727 1728 1729
void UAS::requestParameters()
{
    mavlink_message_t msg;
LM's avatar
LM committed
1730
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
1731
    sendMessage(msg);
Lorenz Meier's avatar
Lorenz Meier committed
1732
    qDebug() << __FILE__ << __LINE__ << "LOADING PARAM LIST";
1733 1734
}

1735
void UAS::writeParametersToStorage()
1736
{
1737
    mavlink_message_t msg;
1738
    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
1739
    qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
1740
    sendMessage(msg);
1741 1742 1743 1744
}

void UAS::readParametersFromStorage()
{
1745
    mavlink_message_t msg;
1746
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
1747
    sendMessage(msg);
lm's avatar
lm committed
1748 1749
}

1750
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1751 1752
{
    // Buffers to write data to
1753
    mavlink_message_t msg;
1754
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1755 1756
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1757
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1758 1759
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1760 1761
    // 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
1762 1763
    stream.req_message_rate = 0;
    // Start / stop the message
1764
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1765 1766 1767 1768 1769
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
1770
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1771 1772
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1773 1774
}

1775
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1776 1777 1778
{
    // Buffers to write data to
    mavlink_message_t msg;
1779
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1780
    // Select the message to request from now on
1781
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1782
    // Select the update rate in Hz the message should be send
1783
    stream.req_message_rate = rate;
lm's avatar
lm committed
1784
    // Start / stop the message
1785
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1786 1787 1788 1789 1790
    // 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
1791
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1792 1793
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1794 1795
}

1796
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1797
{
1798 1799 1800 1801
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1802
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1803
    // Select the update rate in Hz the message should be send
1804
    stream.req_message_rate = rate;
1805
    // Start / stop the message
1806
    stream.start_stop = (rate) ? 1 : 0;
1807 1808 1809 1810 1811 1812
    // 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);
1813 1814
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1815
}
1816

1817
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1818
{
1819 1820 1821 1822 1823
#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
1824 1825 1826
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1827
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1828
    // Select the update rate in Hz the message should be send
1829
    stream.req_message_rate = rate;
1830
    // Start / stop the message
1831
    stream.start_stop = (rate) ? 1 : 0;
1832 1833 1834 1835 1836 1837
    // 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);
1838 1839
    // Send message twice to increase chance of reception
    sendMessage(msg);
1840
#endif
lm's avatar
lm committed
1841 1842
}

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

lm's avatar
lm committed
1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884
//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);
//}
1885

1886
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1887 1888 1889 1890 1891
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1892
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1893
    // Select the update rate in Hz the message should be send
1894
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1895
    // Start / stop the message
1896
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1897 1898 1899 1900 1901 1902 1903 1904 1905 1906
    // 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);
}

1907
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1908 1909 1910 1911 1912
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1913
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1914
    // Select the update rate in Hz the message should be send
1915
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1916
    // Start / stop the message
1917
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1918 1919 1920 1921 1922 1923 1924 1925 1926 1927 1928
    // 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);
}

1929
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1930 1931 1932 1933 1934
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1935
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1936
    // Select the update rate in Hz the message should be send
1937
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1938
    // Start / stop the message
1939
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1940 1941 1942 1943 1944 1945 1946 1947 1948 1949 1950
    // 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);
}

1951
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1952 1953 1954 1955 1956
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1957
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1958
    // Select the update rate in Hz the message should be send
1959
    stream.req_message_rate = rate;
1960
    // Start / stop the message
1961
    stream.start_stop = (rate) ? 1 : 0;
1962 1963 1964 1965 1966 1967
    // 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);
1968 1969
    // Send message twice to increase chance of reception
    sendMessage(msg);
1970
    sendMessage(msg);
1971 1972
}

lm's avatar
lm committed
1973 1974 1975 1976 1977 1978 1979
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1980
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
lm's avatar
lm committed
1981
{
1982 1983
    if (!id.isNull())
    {
1984 1985
        mavlink_message_t msg;
        mavlink_param_set_t p;
1986 1987 1988 1989 1990 1991 1992
        mavlink_param_union_t union_value;

        // Assign correct value based on QVariant
        switch (value.type())
        {
        case QVariant::Int:
            union_value.param_int32 = value.toInt();
1993
            p.param_type = MAVLINK_TYPE_INT32_T;
1994 1995 1996
            break;
        case QVariant::UInt:
            union_value.param_uint32 = value.toUInt();
1997
            p.param_type = MAVLINK_TYPE_UINT32_T;
1998 1999 2000
            break;
        case QMetaType::Float:
            union_value.param_float = value.toFloat();
2001
            p.param_type = MAVLINK_TYPE_FLOAT;
2002 2003 2004 2005 2006 2007 2008
            break;
        default:
            qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
            return;
        }

        p.param_value = union_value.param_float;
2009 2010 2011
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

2012 2013
        qDebug() << "SENT PARAM:" << value;

2014
        // Copy string into buffer, ensuring not to exceed the buffer size
2015 2016
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
2017
            // String characters
2018 2019
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
2020 2021
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
2022 2023 2024 2025 2026
            //        // 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';
            //        }
2027
            // Zero fill
2028 2029
            else
            {
2030 2031
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
2032
        }
2033 2034
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
2035
    }
2036 2037
}

2038 2039 2040 2041 2042 2043 2044 2045 2046 2047 2048 2049 2050 2051
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;
}

2052
void UAS::requestParameter(int component, const QString& parameter)
2053
{
2054
    // Request parameter, use parameter name to request it
2055 2056
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
2057 2058 2059 2060 2061 2062 2063 2064
    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
2065 2066 2067 2068
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
2069
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
2070 2071
}

2072 2073 2074 2075
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
2076 2077 2078 2079
    if (airframe == 0)
    {
        switch (systemType)
        {
lm's avatar
lm committed
2080
        case MAV_TYPE_FIXED_WING:
2081 2082
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
lm's avatar
lm committed
2083
        case MAV_TYPE_QUADROTOR:
2084 2085 2086 2087 2088 2089 2090
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

2091 2092
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
2093 2094 2095 2096 2097 2098 2099
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
2100 2101
}

lm's avatar
lm committed
2102 2103 2104
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
2105
    mavlink_command_long_t cmd;
2106 2107 2108 2109 2110 2111
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
2112 2113 2114
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
2115 2116
    cmd.target_system = uasId;
    cmd.target_component = 0;
2117
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
2118 2119 2120
    sendMessage(msg);
}

2121 2122 2123 2124
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;
2125 2126 2127 2128 2129 2130
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
2131 2132 2133
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
2134 2135
    cmd.target_system = uasId;
    cmd.target_component = component;
2136
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
2137 2138 2139
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
2140
/**
lm's avatar
lm committed
2141
 * Launches the system
pixhawk's avatar
pixhawk committed
2142 2143 2144 2145
 *
 **/
void UAS::launch()
{
2146
    mavlink_message_t msg;
2147
    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);
2148
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2149 2150 2151 2152 2153 2154
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
2155
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
2156
{
2157
    mavlink_message_t msg;
2158
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
2159
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2160 2161 2162 2163 2164 2165
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
2166
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
2167
{
2168
    mavlink_message_t msg;
2169
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
2170
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2171 2172 2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183 2184
}

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
2185 2186
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
2187
    {
2188 2189 2190 2191
        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
2192

LM's avatar
LM committed
2193
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
2194 2195 2196
    }
    else
    {
2197 2198
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2199 2200
}

2201 2202 2203 2204 2205
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2206 2207
void UAS::receiveButton(int buttonIndex)
{
2208 2209
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2210
    case 0:
pixhawk's avatar
pixhawk committed
2211

pixhawk's avatar
pixhawk committed
2212 2213
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2214

pixhawk's avatar
pixhawk committed
2215 2216 2217 2218 2219
        break;
    default:

        break;
    }
2220
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2221 2222 2223

}

2224

pixhawk's avatar
pixhawk committed
2225 2226
void UAS::halt()
{
2227 2228 2229
    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
2230 2231 2232 2233
}

void UAS::go()
{
2234 2235 2236
    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
2237 2238 2239 2240 2241
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
2242 2243 2244 2245 2246 2247 2248 2249 2250
    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
2251 2252 2253 2254 2255 2256 2257 2258
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2259 2260
    // FIXME MAVLINKV10PORTINGNEEDED
    halt();
pixhawk's avatar
pixhawk committed
2261 2262 2263
}

/**
lm's avatar
lm committed
2264
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2265 2266 2267 2268 2269 2270
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
2271
    halt();
lm's avatar
lm committed
2272
    // FIXME MAVLINKV10PORTINGNEEDED
LM's avatar
LM committed
2273 2274 2275 2276 2277 2278 2279 2280 2281 2282 2283 2284 2285 2286 2287 2288 2289 2290 2291 2292 2293 2294 2295 2296
    //    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
2297
    return false;
pixhawk's avatar
pixhawk committed
2298 2299
}

lm's avatar
lm committed
2300 2301 2302 2303 2304
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2305
        startHil();
lm's avatar
lm committed
2306 2307 2308
    }
    else
    {
2309
        stopHil();
lm's avatar
lm committed
2310 2311 2312 2313 2314 2315 2316 2317 2318 2319 2320 2321 2322 2323 2324 2325 2326 2327 2328 2329 2330 2331
    }
}

/**
* @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
2332 2333
                       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
2334 2335 2336 2337 2338 2339 2340
{
    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);
}


2341 2342
void UAS::startHil()
{
lm's avatar
lm committed
2343 2344
    // Connect Flight Gear Link
    simulation->connectSimulation();
2345
    mavlink_message_t msg;
LM's avatar
LM committed
2346
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
2347
    sendMessage(msg);
2348 2349
}

2350 2351
void UAS::stopHil()
{
lm's avatar
lm committed
2352
    simulation->disconnectSimulation();
2353
    mavlink_message_t msg;
LM's avatar
LM committed
2354
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
2355
    sendMessage(msg);
2356 2357 2358
}


pixhawk's avatar
pixhawk committed
2359 2360
void UAS::shutdown()
{
2361 2362 2363 2364 2365
    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
2366

2367 2368 2369
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2370

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

2374 2375 2376 2377
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2378
        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);
2379 2380 2381
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2382 2383
}

2384 2385
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2386
    mavlink_message_t msg;
2387
    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);
2388
    sendMessage(msg);
2389 2390
}

pixhawk's avatar
pixhawk committed
2391 2392 2393
/**
 * @return The name of this system as string in human-readable form
 */
2394
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2395 2396
{
    QString result;
2397 2398
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2399
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2400 2401 2402
    }
    else
    {
pixhawk's avatar
pixhawk committed
2403 2404 2405 2406 2407
        result = name;
    }
    return result;
}

2408 2409 2410 2411 2412
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2413 2414 2415 2416 2417 2418 2419 2420 2421 2422 2423 2424 2425 2426 2427 2428 2429 2430 2431 2432 2433 2434 2435 2436 2437 2438 2439 2440 2441 2442 2443 2444 2445 2446 2447 2448 2449 2450 2451
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;
}

2452 2453 2454
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2455 2456 2457
    uint8_t modeid = id;

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

LM's avatar
LM committed
2459
    // BASE MODE DECODING
pixhawk's avatar
pixhawk committed
2460
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
LM's avatar
LM committed
2461
    {
pixhawk's avatar
pixhawk committed
2462
        mode += "AUTO";
LM's avatar
LM committed
2463
    }
pixhawk's avatar
pixhawk committed
2464
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
LM's avatar
LM committed
2465
    {
LM's avatar
LM committed
2466
        mode += "|GUID";
LM's avatar
LM committed
2467
    }
pixhawk's avatar
pixhawk committed
2468
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
LM's avatar
LM committed
2469
    {
LM's avatar
LM committed
2470
        mode += "|STAB";
LM's avatar
LM committed
2471
    }
pixhawk's avatar
pixhawk committed
2472
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
LM's avatar
LM committed
2473
    {
LM's avatar
LM committed
2474
        mode += "|TEST";
LM's avatar
LM committed
2475
    }
pixhawk's avatar
pixhawk committed
2476
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
LM's avatar
LM committed
2477
    {
LM's avatar
LM committed
2478
        mode += "|MAN";
LM's avatar
LM committed
2479
    }
pixhawk's avatar
pixhawk committed
2480 2481

    if (modeid == 0)
LM's avatar
LM committed
2482
    {
2483
        mode = "PREFLIGHT";
LM's avatar
LM committed
2484 2485 2486
    }

    // ARMED STATE DECODING
pixhawk's avatar
pixhawk committed
2487
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
LM's avatar
LM committed
2488
    {
LM's avatar
LM committed
2489
        mode.prepend("A/");
LM's avatar
LM committed
2490 2491 2492
    }
    else
    {
LM's avatar
LM committed
2493
        mode.prepend("D/");
LM's avatar
LM committed
2494 2495 2496
    }

    // HARDWARE IN THE LOOP DECODING
pixhawk's avatar
pixhawk committed
2497
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
LM's avatar
LM committed
2498 2499
    {
        mode.prepend("HIL:");
2500 2501 2502 2503 2504
    }

    return mode;
}

2505 2506 2507 2508 2509
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2510 2511
void UAS::addLink(LinkInterface* link)
{
2512 2513
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2514
        links->append(link);
2515
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2516 2517 2518
    }
}

2519 2520 2521
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2522 2523
    if (link)
    {
2524 2525 2526 2527
        links->removeAt(links->indexOf(link));
    }
}

LM's avatar
LM committed
2528

pixhawk's avatar
pixhawk committed
2529 2530 2531 2532 2533
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}

LM's avatar
LM committed
2534 2535 2536 2537 2538
QMap<int, QString> UAS::getComponents()
{
    return components;
}

pixhawk's avatar
pixhawk committed
2539 2540 2541 2542 2543 2544


void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2545 2546
    switch (batteryType)
    {
lm's avatar
lm committed
2547
    case NICD:
pixhawk's avatar
pixhawk committed
2548
        break;
lm's avatar
lm committed
2549
    case NIMH:
pixhawk's avatar
pixhawk committed
2550
        break;
lm's avatar
lm committed
2551
    case LIION:
pixhawk's avatar
pixhawk committed
2552
        break;
lm's avatar
lm committed
2553
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2554 2555 2556
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2557
    case LIFE:
pixhawk's avatar
pixhawk committed
2558
        break;
lm's avatar
lm committed
2559
    case AGZN:
pixhawk's avatar
pixhawk committed
2560 2561 2562 2563
        break;
    }
}

2564 2565
void UAS::setBatterySpecs(const QString& specs)
{
2566 2567
    if (specs.length() == 0 || specs.contains("%"))
    {
2568
        batteryRemainingEstimateEnabled = false;
2569
        bool ok;
2570 2571 2572
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2573 2574
        if (ok)
        {
2575
            warnLevelPercent = temp;
2576 2577 2578
        }
        else
        {
2579 2580
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2581 2582 2583
    }
    else
    {
2584 2585 2586 2587 2588
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2589 2590
        if (parts.length() == 3)
        {
2591 2592 2593 2594 2595 2596 2597 2598 2599 2600 2601
            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;
2602 2603 2604
        }
        else
        {
2605 2606
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2607 2608 2609 2610 2611
    }
}

QString UAS::getBatterySpecs()
{
2612 2613
    if (batteryRemainingEstimateEnabled)
    {
2614
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2615 2616 2617
    }
    else
    {
2618 2619
        return QString("%1%").arg(warnLevelPercent);
    }
2620 2621
}

pixhawk's avatar
pixhawk committed
2622 2623
int UAS::calculateTimeRemaining()
{
LM's avatar
LM committed
2624
    quint64 dt = QGC::groundTimeMilliseconds() - startTime;
pixhawk's avatar
pixhawk committed
2625 2626 2627 2628 2629 2630 2631 2632 2633 2634
    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
2635 2636 2637
/**
 * @return charge level in percent - 0 - 100
 */
2638
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2639
{
2640 2641 2642 2643
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2644
            chargeLevel = 0.0f;
2645 2646 2647
        }
        else if (lpVoltage > fullVoltage)
        {
2648
            chargeLevel = 100.0f;
2649 2650 2651
        }
        else
        {
2652 2653
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2654 2655
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2656 2657
}

lm's avatar
lm committed
2658 2659
void UAS::startLowBattAlarm()
{
2660 2661
    if (!lowBattAlarm)
    {
2662
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2663
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2664 2665 2666 2667 2668 2669
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2670 2671
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2672 2673 2674 2675
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}