UAS.cc 91.3 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 708 709
        {
            mavlink_gps_global_origin_t pos;
            mavlink_msg_gps_global_origin_decode(&message, &pos);
            emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
        }
LM's avatar
LM committed
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 926 927
        {
            QByteArray b;
            b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
            mavlink_msg_statustext_get_text(&message, b.data());
            //b.append('\0');
            QString text = QString(b);
            int severity = mavlink_msg_statustext_get_severity(&message);
            //qDebug() << "RECEIVED STATUS:" << text;false
            //emit statusTextReceived(severity, text);
            emit textMessageReceived(uasId, message.compid, severity, text);
        }
LM's avatar
LM committed
928
            break;
929
#ifdef MAVLINK_ENABLED_PIXHAWK
930
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
LM's avatar
LM committed
931 932 933 934 935 936 937 938 939 940 941 942 943
        {
            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
944
            break;
945

946
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
LM's avatar
LM committed
947 948 949 950 951
        {
            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
952

LM's avatar
LM committed
953 954 955 956 957 958 959
            // Check if we have a valid transaction
            if (imagePackets == 0)
            {
                // NO VALID TRANSACTION - ABORT
                // Restart statemachine
                imagePacketsArrived = 0;
            }
960

LM's avatar
LM committed
961 962 963 964
            for (int i = 0; i < imagePayload; ++i)
            {
                if (pos <= imageSize) {
                    imageRecBuffer[pos] = img.data[i];
LM's avatar
LM committed
965
                }
LM's avatar
LM committed
966 967
                ++pos;
            }
968

LM's avatar
LM committed
969
            ++imagePacketsArrived;
970

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

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

1114
#if defined(QGC_PROTOBUF_ENABLED)
1115 1116
void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message)
{
LM's avatar
LM committed
1117 1118 1119 1120
    if (!link)
    {
        return;
    }
1121 1122 1123 1124 1125
    if (!links->contains(link))
    {
        addLink(link);
    }

1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 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
    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;
    }

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

#endif

1207 1208
void UAS::setHomePosition(double lat, double lon, double alt)
{
1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237
    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);
    }
1238 1239
}

1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253
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()));


1254 1255
    if (ret == QMessageBox::Yes)
    {
1256 1257 1258 1259
        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);
1260 1261 1262
    }
}

pixhawk's avatar
pixhawk committed
1263 1264
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1265
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1266
    mavlink_message_t msg;
LM's avatar
LM committed
1267
    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
1268
    sendMessage(msg);
1269
#else
lm's avatar
lm committed
1270 1271 1272 1273
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1274
#endif
pixhawk's avatar
pixhawk committed
1275 1276
}

pixhawk's avatar
pixhawk committed
1277 1278
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1279
#ifdef MAVLINK_ENABLED_PIXHAWK
1280
    mavlink_message_t msg;
1281
    mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
1282
    sendMessage(msg);
lm's avatar
lm committed
1283
#else
1284 1285 1286 1287
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1288 1289 1290 1291
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1292
{
1293 1294
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1295
    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);
1296
    sendMessage(msg);
lm's avatar
lm committed
1297 1298
}

1299
void UAS::startDataRecording()
lm's avatar
lm committed
1300
{
1301
    mavlink_message_t msg;
1302
    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);
1303
    sendMessage(msg);
lm's avatar
lm committed
1304 1305 1306 1307
}

void UAS::stopDataRecording()
{
1308
    mavlink_message_t msg;
1309
    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);
1310
    sendMessage(msg);
lm's avatar
lm committed
1311 1312
}

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

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

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

LM's avatar
LM committed
1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363
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
1364
    else if (time < 1261440000000000)
LM's avatar
LM committed
1365
#endif
LM's avatar
LM committed
1366
    {
LM's avatar
LM committed
1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381
        //        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;
    }
}

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

1452 1453
QList<QString> UAS::getParameterNames(int component)
{
1454 1455
    if (parameters.contains(component))
    {
1456
        return parameters.value(component)->keys();
1457 1458 1459
    }
    else
    {
1460 1461 1462 1463 1464 1465 1466 1467 1468
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1469
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1470
{
LM's avatar
LM committed
1471 1472 1473 1474 1475
    //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
1476 1477 1478 1479 1480
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1481 1482
    foreach (LinkInterface* link, *links)
    {
Lorenz Meier's avatar
Lorenz Meier committed
1483
        qDebug() << "ITERATING THROUGH LINKS";
1484 1485
        if (link)
        {
1486
            sendMessage(link, message);
Lorenz Meier's avatar
Lorenz Meier committed
1487
            qDebug() << "SENT MESSAGE";
1488 1489 1490
        }
        else
        {
1491 1492 1493
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1494 1495 1496
    }
}

1497 1498 1499 1500
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1501

1502 1503 1504 1505
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1506
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1507 1508 1509 1510 1511 1512
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1513
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1514 1515
                        sendMessage(serial, message);
                    }
1516 1517 1518 1519 1520 1521
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1522 1523
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1524
    if(!link) return;
pixhawk's avatar
pixhawk committed
1525 1526 1527
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1528
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1529 1530
    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
1531
    // If link is connected
1532 1533
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1534 1535 1536 1537 1538 1539 1540 1541
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1542
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1543
{
1544
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1545 1546
}

1547 1548
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1549 1550
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
LM's avatar
LM committed
1551 1552 1553 1554 1555 1556 1557 1558
        switch (mode)
        {
        case 0:
            return QString("PREFLIGHT");
            break;
        default:
            return QString("UNKNOWN");
        }
lm's avatar
lm committed
1559 1560 1561 1562 1563 1564 1565 1566 1567
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1568 1569
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1570 1571
}

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

lm's avatar
lm committed
1609
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1610
        uasState = tr("SHUTDOWN");
1611
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1612
        break;
1613

lm's avatar
lm committed
1614
    default:
pixhawk's avatar
pixhawk committed
1615
        uasState = tr("UNKNOWN");
1616
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1617 1618 1619 1620
        break;
    }
}

1621 1622
QImage UAS::getImage()
{
LM's avatar
LM committed
1623 1624 1625 1626 1627 1628 1629
#ifdef MAVLINK_ENABLED_PIXHAWK

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

    // RAW greyscale
    if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
    {
LM's avatar
LM committed
1630 1631
        // TODO FIXME
        int imgColors = 255;//imageSize/(imageWidth*imageHeight);
LM's avatar
LM committed
1632 1633 1634 1635
        //const int headerSize = 15;

        // Construct PGM header
        QString header("P5\n%1 %2\n%3\n");
LM's avatar
LM committed
1636
        header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
LM's avatar
LM committed
1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661

        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
1662
        if (!image.loadFromData(imageRecBuffer))
LM's avatar
LM committed
1663
        {
LM's avatar
LM committed
1664
            qDebug() << "Loading data from image buffer failed!";
LM's avatar
LM committed
1665 1666
        }
    }
1667 1668
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1669
    //imageRecBuffer.clear();
1670
    return image;
1671
#else
LM's avatar
LM committed
1672
    return QImage();
LM's avatar
LM committed
1673
#endif
1674

1675 1676 1677 1678
}

void UAS::requestImage()
{
1679
#ifdef MAVLINK_ENABLED_PIXHAWK
1680 1681
    qDebug() << "trying to get an image from the uas...";

1682 1683 1684
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1685
        mavlink_message_t msg;
LM's avatar
LM committed
1686
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50);
1687 1688
        sendMessage(msg);
    }
1689
#endif
1690
}
pixhawk's avatar
pixhawk committed
1691 1692 1693 1694 1695 1696 1697 1698 1699


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1700
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1701
{
1702 1703
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1704
        return 0;
1705 1706 1707
    }
    else
    {
LM's avatar
LM committed
1708
        return QGC::groundTimeMilliseconds() - startTime;
pixhawk's avatar
pixhawk committed
1709 1710 1711
    }
}

1712
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1713 1714 1715 1716
{
    return commStatus;
}

1717 1718 1719
void UAS::requestParameters()
{
    mavlink_message_t msg;
LM's avatar
LM committed
1720
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
1721
    sendMessage(msg);
Lorenz Meier's avatar
Lorenz Meier committed
1722
    qDebug() << __FILE__ << __LINE__ << "LOADING PARAM LIST";
1723 1724
}

1725
void UAS::writeParametersToStorage()
1726
{
1727
    mavlink_message_t msg;
1728
    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
1729
    qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
1730
    sendMessage(msg);
1731 1732 1733 1734
}

void UAS::readParametersFromStorage()
{
1735
    mavlink_message_t msg;
1736
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
1737
    sendMessage(msg);
lm's avatar
lm committed
1738 1739
}

1740
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1741 1742
{
    // Buffers to write data to
1743
    mavlink_message_t msg;
1744
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1745 1746
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1747
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1748 1749
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1750 1751
    // 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
1752 1753
    stream.req_message_rate = 0;
    // Start / stop the message
1754
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1755 1756 1757 1758 1759
    // 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
1760
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1761 1762
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1763 1764
}

1765
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1766 1767 1768
{
    // Buffers to write data to
    mavlink_message_t msg;
1769
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1770
    // Select the message to request from now on
1771
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1772
    // Select the update rate in Hz the message should be send
1773
    stream.req_message_rate = rate;
lm's avatar
lm committed
1774
    // Start / stop the message
1775
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1776 1777 1778 1779 1780
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
1781
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1782 1783
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1784 1785
}

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

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

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

lm's avatar
lm committed
1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874
//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);
//}
1875

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

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

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

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

lm's avatar
lm committed
1963 1964 1965 1966 1967 1968 1969
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1970
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
lm's avatar
lm committed
1971
{
1972 1973
    if (!id.isNull())
    {
1974 1975
        mavlink_message_t msg;
        mavlink_param_set_t p;
1976 1977 1978 1979 1980 1981 1982
        mavlink_param_union_t union_value;

        // Assign correct value based on QVariant
        switch (value.type())
        {
        case QVariant::Int:
            union_value.param_int32 = value.toInt();
1983
            p.param_type = MAVLINK_TYPE_INT32_T;
1984 1985 1986
            break;
        case QVariant::UInt:
            union_value.param_uint32 = value.toUInt();
1987
            p.param_type = MAVLINK_TYPE_UINT32_T;
1988 1989 1990
            break;
        case QMetaType::Float:
            union_value.param_float = value.toFloat();
1991
            p.param_type = MAVLINK_TYPE_FLOAT;
1992 1993 1994 1995 1996 1997 1998
            break;
        default:
            qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
            return;
        }

        p.param_value = union_value.param_float;
1999 2000 2001
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

2002 2003
        qDebug() << "SENT PARAM:" << value;

2004
        // Copy string into buffer, ensuring not to exceed the buffer size
2005 2006
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
2007
            // String characters
2008 2009
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
2010 2011
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
2012 2013 2014 2015 2016
            //        // 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';
            //        }
2017
            // Zero fill
2018 2019
            else
            {
2020 2021
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
2022
        }
2023 2024
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
2025
    }
2026 2027
}

2028 2029 2030 2031 2032 2033 2034 2035 2036 2037 2038 2039 2040 2041
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;
}

2042
void UAS::requestParameter(int component, const QString& parameter)
2043
{
2044
    // Request parameter, use parameter name to request it
2045 2046
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
2047 2048 2049 2050 2051 2052 2053 2054
    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
2055 2056 2057 2058
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
2059
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
2060 2061
}

2062 2063 2064 2065
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
2066 2067 2068 2069
    if (airframe == 0)
    {
        switch (systemType)
        {
lm's avatar
lm committed
2070
        case MAV_TYPE_FIXED_WING:
2071 2072
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
lm's avatar
lm committed
2073
        case MAV_TYPE_QUADROTOR:
2074 2075 2076 2077 2078 2079 2080
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

2081 2082
void UAS::setUASName(const QString& name)
{
lm's avatar
lm committed
2083 2084 2085 2086 2087 2088 2089
    if (name != "")
    {
        this->name = name;
        writeSettings();
        emit nameChanged(name);
        emit systemSpecsChanged(uasId);
    }
2090 2091
}

lm's avatar
lm committed
2092 2093 2094
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
2095
    mavlink_command_long_t cmd;
2096 2097 2098 2099 2100 2101
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
2102 2103 2104
    cmd.param5 = 0.0f;
    cmd.param6 = 0.0f;
    cmd.param7 = 0.0f;
2105 2106
    cmd.target_system = uasId;
    cmd.target_component = 0;
2107
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
2108 2109 2110
    sendMessage(msg);
}

2111 2112 2113 2114
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;
2115 2116 2117 2118 2119 2120
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
2121 2122 2123
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
2124 2125
    cmd.target_system = uasId;
    cmd.target_component = component;
2126
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
2127 2128 2129
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
2130
/**
lm's avatar
lm committed
2131
 * Launches the system
pixhawk's avatar
pixhawk committed
2132 2133 2134 2135
 *
 **/
void UAS::launch()
{
2136
    mavlink_message_t msg;
2137
    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);
2138
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2139 2140 2141 2142 2143 2144
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
2145
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
2146
{
2147
    mavlink_message_t msg;
2148
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
2149
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2150 2151 2152 2153 2154 2155
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
2156
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
2157
{
2158
    mavlink_message_t msg;
2159
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
2160
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171 2172 2173 2174
}

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
2175 2176
    // If system has manual inputs enabled and is armed
    if((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY))
2177
    {
2178 2179 2180 2181
        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
2182

LM's avatar
LM committed
2183
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
2184 2185 2186
    }
    else
    {
2187 2188
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2189 2190
}

2191 2192 2193 2194 2195
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2196 2197
void UAS::receiveButton(int buttonIndex)
{
2198 2199
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2200
    case 0:
pixhawk's avatar
pixhawk committed
2201

pixhawk's avatar
pixhawk committed
2202 2203
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2204

pixhawk's avatar
pixhawk committed
2205 2206 2207 2208 2209
        break;
    default:

        break;
    }
2210
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2211 2212 2213

}

2214

pixhawk's avatar
pixhawk committed
2215 2216
void UAS::halt()
{
2217 2218 2219
    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
2220 2221 2222 2223
}

void UAS::go()
{
2224 2225 2226
    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
2227 2228 2229 2230 2231
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
2232 2233 2234 2235 2236 2237 2238 2239 2240
    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
2241 2242 2243 2244 2245 2246 2247 2248
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2249 2250
    // FIXME MAVLINKV10PORTINGNEEDED
    halt();
pixhawk's avatar
pixhawk committed
2251 2252 2253
}

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

lm's avatar
lm committed
2290 2291 2292 2293 2294
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2295
        startHil();
lm's avatar
lm committed
2296 2297 2298
    }
    else
    {
2299
        stopHil();
lm's avatar
lm committed
2300 2301 2302 2303 2304 2305 2306 2307 2308 2309 2310 2311 2312 2313 2314 2315 2316 2317 2318 2319 2320 2321
    }
}

/**
* @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
2322 2323
                       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
2324 2325 2326 2327 2328 2329 2330
{
    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);
}


2331 2332
void UAS::startHil()
{
lm's avatar
lm committed
2333 2334
    // Connect Flight Gear Link
    simulation->connectSimulation();
2335
    mavlink_message_t msg;
LM's avatar
LM committed
2336
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
2337
    sendMessage(msg);
2338 2339
}

2340 2341
void UAS::stopHil()
{
lm's avatar
lm committed
2342
    simulation->disconnectSimulation();
2343
    mavlink_message_t msg;
LM's avatar
LM committed
2344
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
2345
    sendMessage(msg);
2346 2347 2348
}


pixhawk's avatar
pixhawk committed
2349 2350
void UAS::shutdown()
{
2351 2352 2353 2354 2355
    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
2356

2357 2358 2359
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();
lm's avatar
lm committed
2360

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

2364 2365 2366 2367
    if (ret == QMessageBox::Yes)
    {
        // If the active UAS is set, execute command
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2368
        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);
2369 2370 2371
        sendMessage(msg);
        result = true;
    }
pixhawk's avatar
pixhawk committed
2372 2373
}

2374 2375
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2376
    mavlink_message_t msg;
2377
    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);
2378
    sendMessage(msg);
2379 2380
}

pixhawk's avatar
pixhawk committed
2381 2382 2383
/**
 * @return The name of this system as string in human-readable form
 */
2384
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2385 2386
{
    QString result;
2387 2388
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2389
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2390 2391 2392
    }
    else
    {
pixhawk's avatar
pixhawk committed
2393 2394 2395 2396 2397
        result = name;
    }
    return result;
}

2398 2399 2400 2401 2402
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2403 2404 2405 2406 2407 2408 2409 2410 2411 2412 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
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;
}

2442 2443 2444
QString UAS::getShortModeTextFor(int id)
{
    QString mode;
LM's avatar
LM committed
2445 2446 2447
    uint8_t modeid = id;

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

LM's avatar
LM committed
2449
    // BASE MODE DECODING
pixhawk's avatar
pixhawk committed
2450
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
LM's avatar
LM committed
2451
    {
pixhawk's avatar
pixhawk committed
2452
        mode += "AUTO";
LM's avatar
LM committed
2453
    }
pixhawk's avatar
pixhawk committed
2454
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
LM's avatar
LM committed
2455
    {
LM's avatar
LM committed
2456
        mode += "|GUID";
LM's avatar
LM committed
2457
    }
pixhawk's avatar
pixhawk committed
2458
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
LM's avatar
LM committed
2459
    {
LM's avatar
LM committed
2460
        mode += "|STAB";
LM's avatar
LM committed
2461
    }
pixhawk's avatar
pixhawk committed
2462
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
LM's avatar
LM committed
2463
    {
LM's avatar
LM committed
2464
        mode += "|TEST";
LM's avatar
LM committed
2465
    }
pixhawk's avatar
pixhawk committed
2466
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
LM's avatar
LM committed
2467
    {
LM's avatar
LM committed
2468
        mode += "|MAN";
LM's avatar
LM committed
2469
    }
pixhawk's avatar
pixhawk committed
2470 2471

    if (modeid == 0)
LM's avatar
LM committed
2472
    {
2473
        mode = "PREFLIGHT";
LM's avatar
LM committed
2474 2475 2476
    }

    // ARMED STATE DECODING
pixhawk's avatar
pixhawk committed
2477
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
LM's avatar
LM committed
2478
    {
LM's avatar
LM committed
2479
        mode.prepend("A/");
LM's avatar
LM committed
2480 2481 2482
    }
    else
    {
LM's avatar
LM committed
2483
        mode.prepend("D/");
LM's avatar
LM committed
2484 2485 2486
    }

    // HARDWARE IN THE LOOP DECODING
pixhawk's avatar
pixhawk committed
2487
    if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
LM's avatar
LM committed
2488 2489
    {
        mode.prepend("HIL:");
2490 2491 2492 2493 2494
    }

    return mode;
}

2495 2496 2497 2498 2499
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2500 2501
void UAS::addLink(LinkInterface* link)
{
2502 2503
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2504
        links->append(link);
2505
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2506 2507 2508
    }
}

2509 2510 2511
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2512 2513
    if (link)
    {
2514 2515 2516 2517
        links->removeAt(links->indexOf(link));
    }
}

LM's avatar
LM committed
2518

pixhawk's avatar
pixhawk committed
2519 2520 2521 2522 2523
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}

LM's avatar
LM committed
2524 2525 2526 2527 2528
QMap<int, QString> UAS::getComponents()
{
    return components;
}

pixhawk's avatar
pixhawk committed
2529 2530 2531 2532 2533 2534


void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2535 2536
    switch (batteryType)
    {
lm's avatar
lm committed
2537
    case NICD:
pixhawk's avatar
pixhawk committed
2538
        break;
lm's avatar
lm committed
2539
    case NIMH:
pixhawk's avatar
pixhawk committed
2540
        break;
lm's avatar
lm committed
2541
    case LIION:
pixhawk's avatar
pixhawk committed
2542
        break;
lm's avatar
lm committed
2543
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2544 2545 2546
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2547
    case LIFE:
pixhawk's avatar
pixhawk committed
2548
        break;
lm's avatar
lm committed
2549
    case AGZN:
pixhawk's avatar
pixhawk committed
2550 2551 2552 2553
        break;
    }
}

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

QString UAS::getBatterySpecs()
{
2602 2603
    if (batteryRemainingEstimateEnabled)
    {
2604
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2605 2606 2607
    }
    else
    {
2608 2609
        return QString("%1%").arg(warnLevelPercent);
    }
2610 2611
}

pixhawk's avatar
pixhawk committed
2612 2613
int UAS::calculateTimeRemaining()
{
LM's avatar
LM committed
2614
    quint64 dt = QGC::groundTimeMilliseconds() - startTime;
pixhawk's avatar
pixhawk committed
2615 2616 2617 2618 2619 2620 2621 2622 2623 2624
    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
2625 2626 2627
/**
 * @return charge level in percent - 0 - 100
 */
2628
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2629
{
2630 2631 2632 2633
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2634
            chargeLevel = 0.0f;
2635 2636 2637
        }
        else if (lpVoltage > fullVoltage)
        {
2638
            chargeLevel = 100.0f;
2639 2640 2641
        }
        else
        {
2642 2643
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2644 2645
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2646 2647
}

lm's avatar
lm committed
2648 2649
void UAS::startLowBattAlarm()
{
2650 2651
    if (!lowBattAlarm)
    {
2652
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2653
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2654 2655 2656 2657 2658 2659
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2660 2661
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2662 2663 2664 2665
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}