UAS.cc 103 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

Jessica's avatar
Jessica committed
34
35
/**
* Gets the settings from the previous UAS (name, airframe, autopilot, battery specs)
36
37
38
* by calling readSettings. This means the new UAS will have the same settings 
* as the previous one created unless one calls deleteSettings in the code after
* creating the UAS. 
Jessica's avatar
Jessica committed
39
*/
40
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lm's avatar
lm committed
41
42
43
44
45
46
47
48
49
50
51
    uasId(id),
    startTime(QGC::groundTimeMilliseconds()),
    commStatus(COMM_DISCONNECTED),
    name(""),
    autopilot(-1),
    links(new QList<LinkInterface*>()),
    unknownPackets(),
    mavlink(protocol),
    waypointManager(this),
    thrustSum(0),
    thrustMax(10),
52
53
54
55
    startVoltage(-1.0f),
    tickVoltage(10.5f),
    lastTickVoltageValue(13.0f),
    tickLowpassVoltage(12.0f),
lm's avatar
lm committed
56
57
    warnVoltage(9.5f),
    warnLevelPercent(20.0f),
58
    currentVoltage(12.6f),
lm's avatar
lm committed
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
    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
87
    #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
88
    receivedOverlayTimestamp(0.0),
89
90
    receivedObstacleListTimestamp(0.0),
    receivedPathTimestamp(0.0),
91
92
    receivedPointCloudTimestamp(0.0),
    receivedRGBDImageTimestamp(0.0),
LM's avatar
LM committed
93
    #endif
lm's avatar
lm committed
94
    paramsOnceRequested(false),
95
    airframe(QGC_AIRFRAME_GENERIC),
lm's avatar
lm committed
96
97
98
99
    attitudeKnown(false),
    paramManager(NULL),
    attitudeStamped(false),
    lastAttitude(0),
100
    simulation(new QGCXPlaneLink(this)),
lm's avatar
lm committed
101
102
    isLocalPositionKnown(false),
    isGlobalPositionKnown(false),
103
104
    systemIsArmed(false),
    nedPosGlobalOffset(0,0,0),
105
106
    nedAttGlobalOffset(0,0,0),
    connectionLost(false),
107
108
    lastVoltageWarning(0),
    lastNonNullTime(0),
109
110
    onboardTimeOffsetInvalidCount(0),
    hilEnabled(false)
111

pixhawk's avatar
pixhawk committed
112
{
113
114
115
116
117
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
    }
118
    
119
    color = UASInterface::getNextColor();
lm's avatar
lm committed
120
    setBatterySpecs(QString("9V,9.5V,12.6V"));
121
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
122
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
lm's avatar
lm committed
123
    statusTimeout->start(500);
124
125
    readSettings(); 
    type = MAV_TYPE_GENERIC;
126
127
    // Initial signals
    emit disarmed();
128
    emit armingChanged(false);  
pixhawk's avatar
pixhawk committed
129
130
}

Jessica's avatar
Jessica committed
131
132
133
134
/**
* Saves the settings of name, airframe, autopilot type and battery specifications
* by calling writeSettings.
*/
pixhawk's avatar
pixhawk committed
135
136
UAS::~UAS()
{
137
    writeSettings();
pixhawk's avatar
pixhawk committed
138
    delete links;
139
140
    delete statusTimeout;
    delete simulation;
141
}
Jessica's avatar
Jessica committed
142
143

/**
144
145
* Saves the settings of name, airframe, autopilot type and battery specifications
* for the next instantiation of UAS.
Jessica's avatar
Jessica committed
146
*/
147
148
149
150
151
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
152
153
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
154
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
155
156
157
158
    settings.endGroup();
    settings.sync();
}

Jessica's avatar
Jessica committed
159
/**
160
161
162
* Reads in the settings: name, airframe, autopilot type, and battery specifications
* for the new UAS.
*/
163
164
165
166
167
void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
168
169
    this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
    this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
Lorenz Meier's avatar
Lorenz Meier committed
170
171
    if (settings.contains("BATTERY_SPECS"))
    {
172
173
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
174
175
176
    settings.endGroup();
}

Jessica's avatar
Jessica committed
177
/**
178
179
180
181
*  Deletes the settings origianally read into the UAS by readSettings.
*  This is in case one does not want the old values but would rather 
*  start with the values assigned by the constructor.
*/
182
183
184
void UAS::deleteSettings()
{
    this->name = "";
185
    this->airframe = QGC_AIRFRAME_GENERIC;
186
    this->autopilot = -1;
187
    setBatterySpecs(QString("9V,9.5V,12.6V"));
188
189
}

Jessica's avatar
Jessica committed
190
191
/**
* @ return the id of the uas
192
*/
193
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
194
195
196
197
{
    return uasId;
}

Jessica's avatar
Jessica committed
198
/**
199
* Update the heartbeat.
Jessica's avatar
Jessica committed
200
*/
201
202
void UAS::updateState()
{
lm's avatar
lm committed
203
204
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
205
    if (!connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
lm's avatar
lm committed
206
    {
207
208
209
210
211
        connectionLost = true;
        QString audiostring = QString("Link lost to system %1").arg(this->getUASID());
        GAudioOutput::instance()->say(audiostring.toLower());
    }

212
213
214
215
    // Update connection loss time on each iteration
    if (connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
    {
        connectionLossTime = heartbeatInterval;
216
        emit heartbeatTimeout(true, heartbeatInterval/1000);
217
218
    }

219
220
221
222
223
224
225
    // Connection gained
    if (connectionLost && (heartbeatInterval < timeoutIntervalHeartbeat))
    {
        QString audiostring = QString("Link regained to system %1 after %2 seconds").arg(this->getUASID()).arg((int)(connectionLossTime/1000000));
        GAudioOutput::instance()->say(audiostring.toLower());
        connectionLost = false;
        connectionLossTime = 0;
226
        emit heartbeatTimeout(false, 0);
lm's avatar
lm committed
227
228
    }

229
230
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
lm's avatar
lm committed
231
232
    if (positionLock)
    {
233
        positionLock = false;
lm's avatar
lm committed
234
235
236
    }
    else
    {
lm's avatar
lm committed
237
        if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock)
lm's avatar
lm committed
238
        {
239
240
241
            GAudioOutput::instance()->notifyNegative();
        }
    }
Lorenz Meier's avatar
Lorenz Meier committed
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269

//#define MAVLINK_OFFBOARD_CONTROL_MODE_NONE 0
//#define MAVLINK_OFFBOARD_CONTROL_MODE_RATES 1
//#define MAVLINK_OFFBOARD_CONTROL_MODE_ATTITUDE 2
//#define MAVLINK_OFFBOARD_CONTROL_MODE_VELOCITY 3
//#define MAVLINK_OFFBOARD_CONTROL_MODE_POSITION 4
//#define MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED 0x10

//#warning THIS IS A HUGE HACK AND SHOULD NEVER SHOW UP IN ANY GIT REPOSITORY
//    mavlink_message_t message;

//            mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t sp;

//            sp.group = 0;

//            /* set rate mode, set zero rates and 20% throttle */
//            sp.mode = MAVLINK_OFFBOARD_CONTROL_MODE_RATES | MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED;

//            sp.roll[0] = INT16_MAX * 0.0f;
//            sp.pitch[0] = INT16_MAX * 0.0f;
//            sp.yaw[0] = INT16_MAX * 0.0f;
//            sp.thrust[0] = UINT16_MAX * 0.3f;


//            /* send from system 200 and component 0 */
//            mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(200, 0, &message, &sp);

//            sendMessage(message);
270
271
}

Jessica's avatar
Jessica committed
272
/**
273
274
275
* If the acitve UAS (the UAS that was selected) is not the one that is currently
* active, then change the active UAS to the one that was selected.
*/
pixhawk's avatar
pixhawk committed
276
277
void UAS::setSelected()
{
278
279
    if (UASManager::instance()->getActiveUAS() != this)
    {
280
281
282
283
284
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

Jessica's avatar
Jessica committed
285
/**
286
* @return if the active UAS is the current UAS
Jessica's avatar
Jessica committed
287
**/
288
289
290
bool UAS::getSelected() const
{
    return (UASManager::instance()->getActiveUAS() == this);
pixhawk's avatar
pixhawk committed
291
292
293
294
}

void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
295
    if (!link) return;
296
297
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
298
        addLink(link);
299
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
300
301
    }

LM's avatar
LM committed
302
303
304
305
306
307
308
    if (!components.contains(message.compid))
    {
        QString componentName;

        switch (message.compid)
        {
        case MAV_COMP_ID_ALL:
LM's avatar
LM committed
309
310
311
312
        {
            componentName = "ANONYMOUS";
            break;
        }
LM's avatar
LM committed
313
        case MAV_COMP_ID_IMU:
LM's avatar
LM committed
314
315
316
317
        {
            componentName = "IMU #1";
            break;
        }
LM's avatar
LM committed
318
        case MAV_COMP_ID_CAMERA:
LM's avatar
LM committed
319
320
321
322
        {
            componentName = "CAMERA";
            break;
        }
LM's avatar
LM committed
323
        case MAV_COMP_ID_MISSIONPLANNER:
LM's avatar
LM committed
324
325
326
327
        {
            componentName = "MISSIONPLANNER";
            break;
        }
LM's avatar
LM committed
328
329
330
331
332
333
        }

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

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

LM's avatar
LM committed
336
337
338
339
    // 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))
340
    {
pixhawk's avatar
pixhawk committed
341
342
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
343

344
345
346
        bool multiComponentSourceDetected = false;
        bool wrongComponent = false;

347
348
349
350
351
352
353
354
355
356
357
        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;
        }

358
359
360
        // Store component ID
        if (componentID[message.msgid] == -1)
        {
361
            // Prefer the first component
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
            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;


377
378
        switch (message.msgid)
        {
pixhawk's avatar
pixhawk committed
379
        case MAVLINK_MSG_ID_HEARTBEAT:
lm's avatar
lm committed
380
        {
LM's avatar
LM committed
381
382
383
384
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
lm's avatar
lm committed
385
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
386
            emit heartbeat(this);
lm's avatar
lm committed
387
388
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
389
390
391
392
393
			
			// 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);
394
395
396
			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);
397
			
pixhawk's avatar
pixhawk committed
398
            // Set new type if it has changed
lm's avatar
lm committed
399
            if (this->type != state.type)
400
            {
lm's avatar
lm committed
401
                this->type = state.type;
402
403
404
405
                if (airframe == 0)
                {
                    switch (type)
                    {
lm's avatar
lm committed
406
                    case MAV_TYPE_FIXED_WING:
407
408
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
lm's avatar
lm committed
409
                    case MAV_TYPE_QUADROTOR:
410
411
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
412
413
414
                    case MAV_TYPE_HEXAROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
                        break;
415
416
417
418
419
                    default:
                        // Do nothing
                        break;
                    }
                }
lm's avatar
lm committed
420
                this->autopilot = state.autopilot;
pixhawk's avatar
pixhawk committed
421
422
                emit systemTypeSet(this, type);
            }
423

424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
            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();
                }
            }
439

440
            QString audiostring = QString("System %1").arg(uasId);
lm's avatar
lm committed
441
442
443
444
445
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
446

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

449
450

            if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT)
lm's avatar
lm committed
451
452
453
454
455
456
            {
                statechanged = true;
                this->status = state.system_status;
                getStatusForCode((int)state.system_status, uasState, stateDescription);
                emit statusChanged(this, uasState, stateDescription);
                emit statusChanged(this->status);
457

lm's avatar
lm committed
458
                shortStateText = uasState;
459

460
461
462
463
464
465
466
                // Adjust for better audio
                if (uasState == QString("STANDBY")) uasState = QString("standing by");
                if (uasState == QString("EMERGENCY")) uasState = QString("emergency condition");
                if (uasState == QString("CRITICAL")) uasState = QString("critical condition");
                if (uasState == QString("SHUTDOWN")) uasState = QString("shutting down");

                stateAudio = uasState;
lm's avatar
lm committed
467
            }
lm's avatar
lm committed
468

469
            if (this->mode != static_cast<int>(state.base_mode))
lm's avatar
lm committed
470
471
            {
                modechanged = true;
472
                this->mode = static_cast<int>(state.base_mode);
lm's avatar
lm committed
473
                shortModeText = getShortModeTextFor(this->mode);
474

lm's avatar
lm committed
475
                emit modeChanged(this->getUASID(), shortModeText, "");
LM's avatar
LM committed
476

477
                modeAudio = " is now in " + audiomodeText;
lm's avatar
lm committed
478
            }
LM's avatar
LM committed
479

480
            if (navMode != state.custom_mode)
lm's avatar
lm committed
481
            {
482
483
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
LM's avatar
LM committed
484
                //navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
lm's avatar
lm committed
485
            }
486

lm's avatar
lm committed
487
488
489
490
491
492
493
494
495
496
497
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
498

Lorenz Meier's avatar
Lorenz Meier committed
499
            if (statechanged && ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY))
lm's avatar
lm committed
500
            {
501
502
                GAudioOutput::instance()->say(QString("emergency for system %1").arg(this->getUASID()));
                QTimer::singleShot(3000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
503
504
505
506
            }
            else if (modechanged || statechanged)
            {
                GAudioOutput::instance()->stopEmergency();
507
                GAudioOutput::instance()->say(audiostring.toLower());
lm's avatar
lm committed
508
            }
LM's avatar
LM committed
509
        }
510

lm's avatar
lm committed
511
512
513
            break;
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
LM's avatar
LM committed
514
515
516
517
518
519
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_sys_status_t state;
            mavlink_msg_sys_status_decode(&message, &state);
520

521
522
523
524
525
526
527
528
529
			// 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);
530
            emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);
531
532

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

536
			// Battery charge/time remaining/voltage calculations
LM's avatar
LM committed
537
538
            currentVoltage = state.voltage_battery/1000.0f;
            lpVoltage = filterVoltage(currentVoltage);
539
            tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage;
LM's avatar
LM committed
540

541

542
543
544
545
546
547
548
            // 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)
549
550
551
552
553
                    /* warn if lower than treshold */
                    && (lpVoltage < tickVoltage)
                    /* warn only if we have at least the voltage of an empty LiPo cell, else we're sampling something wrong */
                    && (currentVoltage > 3.3f)
                    /* warn only if current voltage is really still lower by a reasonable amount */
554
                    && ((currentVoltage - 0.2f) < tickVoltage)
555
556
                    /* warn only every 12 seconds */
                    && (QGC::groundTimeUsecs() - lastVoltageWarning) > 12000000)
557
            {
558
559
                GAudioOutput::instance()->say(QString("voltage warning: %1 volts").arg(lpVoltage, 0, 'f', 1, QChar(' ')));
                lastVoltageWarning = QGC::groundTimeUsecs();
560
561
562
563
                lastTickVoltageValue = tickLowpassVoltage;
            }

            if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage;
LM's avatar
LM committed
564
565
566
567
568
569
            timeRemaining = calculateTimeRemaining();
            if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
            {
                chargeLevel = state.battery_remaining;
            }
            emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
570
571
572
573
574
575
576
577
578
			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);
			}
579

LM's avatar
LM committed
580
            // LOW BATTERY ALARM
581
            if (lpVoltage < warnVoltage && (currentVoltage - 0.2f) < warnVoltage && (currentVoltage > 3.3))
LM's avatar
LM committed
582
583
            {
                startLowBattAlarm();
584
            }
LM's avatar
LM committed
585
            else
LM's avatar
LM committed
586
            {
LM's avatar
LM committed
587
                stopLowBattAlarm();
pixhawk's avatar
pixhawk committed
588
            }
589

590
591
592
593
594
595
596
            // 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));

597
598
599
600
601
602
			// 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)
			{
603
				state.drop_rate_comm = 10000;
604
			}
605
606
			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);
607
		}
LM's avatar
LM committed
608
            break;
pixhawk's avatar
pixhawk committed
609
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
610
611
612
613
        {
            mavlink_attitude_t attitude;
            mavlink_msg_attitude_decode(&message, &attitude);
            quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
614

LM's avatar
LM committed
615
            emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time);
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644

            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
645
        }
LM's avatar
LM committed
646
            break;
647
648
649
650
651
652
653
654
655
656
657
658
        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
659
        case MAVLINK_MSG_ID_HIL_CONTROLS:
LM's avatar
LM committed
660
661
662
663
664
        {
            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
665
            break;
666
        case MAVLINK_MSG_ID_VFR_HUD:
LM's avatar
LM committed
667
668
669
670
671
672
        {
            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
673

LM's avatar
LM committed
674
675
676
677
            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
678
            }
LM's avatar
LM committed
679
680
681
682

            emit altitudeChanged(uasId, hud.alt);
            emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
        }
LM's avatar
LM committed
683
            break;
lm's avatar
lm committed
684
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
lm's avatar
lm committed
685
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
686
            //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
687
688
689
690
        {
            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
691

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

LM's avatar
LM committed
695

LM's avatar
LM committed
696
697
698
699
700
            if (!wrongComponent)
            {
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
701

LM's avatar
LM committed
702
                // Emit
703

LM's avatar
LM committed
704
705
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
706

LM's avatar
LM committed
707
708
709
710
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
LM's avatar
LM committed
711
                }
LM's avatar
LM committed
712
713
                positionLock = true;
                isLocalPositionKnown = true;
714
            }
LM's avatar
LM committed
715
        }
716
717
            break;
        case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
LM's avatar
LM committed
718
719
720
721
722
723
724
        {
            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
725
            break;
726
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
727
728
            //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
729
730
731
732
733
734
735
736
737
738
739
740
        {
            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);
741

LM's avatar
LM committed
742
743
            // Set internal state
            if (!positionLock)
LM's avatar
LM committed
744
            {
LM's avatar
LM committed
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
                // 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);
763
764
765
766
767
768
769
770
771
            
            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
772
773

            if (pos.fix_type > 2)
LM's avatar
LM committed
774
            {
LM's avatar
LM committed
775
                emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
LM's avatar
LM committed
776
777
778
779
                latitude = pos.lat/(double)1E7;
                longitude = pos.lon/(double)1E7;
                altitude = pos.alt/1000.0;
                positionLock = true;
780
                isGlobalPositionKnown = true;
LM's avatar
LM committed
781

LM's avatar
LM committed
782
783
784
                // Check for NaN
                int alt = pos.alt;
                if (!isnan(alt) && !isinf(alt))
785
                {
LM's avatar
LM committed
786
787
788
789
790
                    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
791

LM's avatar
LM committed
792
                float vel = pos.vel/100.0f;
LM's avatar
LM committed
793

LM's avatar
LM committed
794
795
796
797
798
799
800
801
802
                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
803
804
                }
            }
LM's avatar
LM committed
805
        }
LM's avatar
LM committed
806
            break;
807
        case MAVLINK_MSG_ID_GPS_STATUS:
LM's avatar
LM committed
808
809
810
811
        {
            mavlink_gps_status_t pos;
            mavlink_msg_gps_status_decode(&message, &pos);
            for(int i = 0; i < (int)pos.satellites_visible; i++)
812
            {
LM's avatar
LM committed
813
                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]));
814
            }
LM's avatar
LM committed
815
        }
LM's avatar
LM committed
816
            break;
817
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
LM's avatar
LM committed
818
819
820
        {
            mavlink_gps_global_origin_t pos;
            mavlink_msg_gps_global_origin_decode(&message, &pos);
821
            emit homePositionChanged(uasId, pos.latitude / 10000000.0, pos.longitude / 10000000.0, pos.altitude / 1000.0);
LM's avatar
LM committed
822
        }
LM's avatar
LM committed
823
            break;
824
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
LM's avatar
LM committed
825
826
827
828
829
830
831
832
833
834
835
836
837
        {
            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
838
            break;
839
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
LM's avatar
LM committed
840
841
842
843
844
845
846
847
848
849
850
851
852
        {
            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
853
            break;
854
        case MAVLINK_MSG_ID_PARAM_VALUE:
LM's avatar
LM committed
855
856
857
858
        {
            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);
Lorenz Meier's avatar
Lorenz Meier committed
859
860
861
            // Construct a string stopping at the first NUL (0) character, else copy the whole
            // byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe)
            QString parameterName(bytes);
LM's avatar
LM committed
862
863
864
865
866
867
868
            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))
869
            {
LM's avatar
LM committed
870
871
                parameters.insert(component, new QMap<QString, QVariant>());
            }
872

LM's avatar
LM committed
873
874
            // Insert parameter into registry
            if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
875

LM's avatar
LM committed
876
877
878
            // Insert with correct type
            switch (value.param_type)
            {
879
            case MAV_PARAM_TYPE_REAL32:
LM's avatar
LM committed
880
881
882
883
884
885
886
            {
                // 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);
887
//                qDebug() << "RECEIVED PARAM:" << param;
LM's avatar
LM committed
888
            }
LM's avatar
LM committed
889
                break;
890
            case MAV_PARAM_TYPE_UINT32:
LM's avatar
LM committed
891
892
893
894
895
896
897
            {
                // 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);
898
//                qDebug() << "RECEIVED PARAM:" << param;
LM's avatar
LM committed
899
            }
LM's avatar
LM committed
900
                break;
901
            case MAV_PARAM_TYPE_INT32:
LM's avatar
LM committed
902
903
904
905
906
907
908
            {
                // 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);
909
//                qDebug() << "RECEIVED PARAM:" << param;
LM's avatar
LM committed
910
911
912
913
914
915
            }
                break;
            default:
                qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
            }
        }
LM's avatar
LM committed
916
            break;
lm's avatar
lm committed
917
        case MAVLINK_MSG_ID_COMMAND_ACK:
918
        {
lm's avatar
lm committed
919
920
            mavlink_command_ack_t ack;
            mavlink_msg_command_ack_decode(&message, &ack);
921
922
923
            switch (ack.result)
            {
            case MAV_RESULT_ACCEPTED:
924
            {
lm's avatar
lm committed
925
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
926
            }
927
928
                break;
            case MAV_RESULT_TEMPORARILY_REJECTED:
929
            {
930
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Temporarily rejected CMD: %1").arg(ack.command));
931
            }
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
                break;
            case MAV_RESULT_DENIED:
            {
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Denied CMD: %1").arg(ack.command));
            }
                break;
            case MAV_RESULT_UNSUPPORTED:
            {
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Unsupported CMD: %1").arg(ack.command));
            }
                break;
            case MAV_RESULT_FAILED:
            {
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Failed CMD: %1").arg(ack.command));
            }
                break;
            }
        }
LM's avatar
LM committed
950
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
LM's avatar
LM committed
951
952
953
954
955
956
        {
            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
957
            break;
lm's avatar
lm committed
958
        case MAVLINK_MSG_ID_MISSION_COUNT:
LM's avatar
LM committed
959
960
961
        {
            mavlink_mission_count_t wpc;
            mavlink_msg_mission_count_decode(&message, &wpc);
Lorenz Meier's avatar
Lorenz Meier committed
962
            if(wpc.target_system == mavlink->getSystemId() || wpc.target_system == 0)
963
            {
LM's avatar
LM committed
964
                waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
pixhawk's avatar
pixhawk committed
965
            }
LM's avatar
LM committed
966
967
            else
            {
Lorenz Meier's avatar
Lorenz Meier committed
968
                qDebug() << "Got waypoint message, but was wrong system id" << wpc.target_system;
LM's avatar
LM committed
969
970
            }
        }
LM's avatar
LM committed
971
            break;
pixhawk's avatar
pixhawk committed
972

lm's avatar
lm committed
973
        case MAVLINK_MSG_ID_MISSION_ITEM:
LM's avatar
LM committed
974
975
976
977
        {
            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;
Lorenz Meier's avatar
Lorenz Meier committed
978
            if(wp.target_system == mavlink->getSystemId() || wp.target_system == 0)
979
            {
LM's avatar
LM committed
980
981
982
983
                waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
            }
            else
            {
Lorenz Meier's avatar
Lorenz Meier committed
984
                qDebug() << "Got waypoint message, but was wrong system id" << wp.target_system;
985
            }
LM's avatar
LM committed
986
        }
LM's avatar
LM committed
987
            break;
pixhawk's avatar
merged    
pixhawk committed
988

lm's avatar
lm committed
989
        case MAVLINK_MSG_ID_MISSION_ACK:
LM's avatar
LM committed
990
991
992
        {
            mavlink_mission_ack_t wpa;
            mavlink_msg_mission_ack_decode(&message, &wpa);
Lorenz Meier's avatar
Lorenz Meier committed
993
994
            if((wpa.target_system == mavlink->getSystemId() || wpa.target_system == 0) &&
                    (wpa.target_component == mavlink->getComponentId() || wpa.target_component == 0))
995
            {
LM's avatar
LM committed
996
                waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
997
            }
LM's avatar
LM committed
998
        }
LM's avatar
LM committed
999
            break;
1000

For faster browsing, not all history is shown. View entire blame