Newer
Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
/*===================================================================
======================================================================*/
/**
* @file
* @brief Represents one unmanned aerial vehicle
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QList>
#include <QMessageBox>
#include <QTimer>
#include <QSettings>
#include <iostream>
#include <QDebug>
#include <cmath>
#include <qmath.h>
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
#include "QGC.h"
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
#include "QGCMAVLink.h"
#include "LinkManager.h"
#include "SerialLink.h"
#ifdef QGC_PROTOBUF_ENABLED
#include <google/protobuf/descriptor.h>
#endif
/**
* Gets the settings from the previous UAS (name, airframe, autopilot, battery specs)
* 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.
*/
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id),
startTime(QGC::groundTimeMilliseconds()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(-1),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
waypointManager(this),
thrustSum(0),
thrustMax(10),
startVoltage(-1.0f),
tickVoltage(10.5f),
lastTickVoltageValue(13.0f),
tickLowpassVoltage(12.0f),
warnVoltage(9.5f),
warnLevelPercent(20.0f),
currentVoltage(12.6f),
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),
globalEstimatorActive(false),
latitude_gps(0.0),
longitude_gps(0.0),
altitude_gps(0.0),
roll(0.0),
pitch(0.0),
yaw(0.0),
statusTimeout(new QTimer(this)),
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
receivedOverlayTimestamp(0.0),
receivedObstacleListTimestamp(0.0),
receivedPathTimestamp(0.0),
receivedPointCloudTimestamp(0.0),
receivedRGBDImageTimestamp(0.0),
#endif
paramsOnceRequested(false),
airframe(QGC_AIRFRAME_GENERIC),
attitudeKnown(false),
paramManager(NULL),
attitudeStamped(false),
lastAttitude(0),
simulation(0),
isLocalPositionKnown(false),
isGlobalPositionKnown(false),
systemIsArmed(false),
nedPosGlobalOffset(0,0,0),
nedAttGlobalOffset(0,0,0),
connectionLost(false),
lastVoltageWarning(0),
lastNonNullTime(0),
onboardTimeOffsetInvalidCount(0),
hilEnabled(false),
sensorHil(false),
lastSendTimeGPS(0),
lastSendTimeSensors(0)
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
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
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
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
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
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
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
{
for (unsigned int i = 0; i<255;++i)
{
componentID[i] = -1;
componentMulti[i] = false;
}
color = UASInterface::getNextColor();
setBatterySpecs(QString("9V,9.5V,12.6V"));
connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
statusTimeout->start(500);
readSettings();
type = MAV_TYPE_GENERIC;
// Initial signals
emit disarmed();
emit armingChanged(false);
}
/**
* Saves the settings of name, airframe, autopilot type and battery specifications
* by calling writeSettings.
*/
UAS::~UAS()
{
writeSettings();
delete links;
delete statusTimeout;
delete simulation;
}
/**
* Saves the settings of name, airframe, autopilot type and battery specifications
* for the next instantiation of UAS.
*/
void UAS::writeSettings()
{
QSettings settings;
settings.beginGroup(QString("MAV%1").arg(uasId));
settings.setValue("NAME", this->name);
settings.setValue("AIRFRAME", this->airframe);
settings.setValue("AP_TYPE", this->autopilot);
settings.setValue("BATTERY_SPECS", getBatterySpecs());
settings.endGroup();
settings.sync();
}
/**
* Reads in the settings: name, airframe, autopilot type, and battery specifications
* for the new UAS.
*/
void UAS::readSettings()
{
QSettings settings;
settings.beginGroup(QString("MAV%1").arg(uasId));
this->name = settings.value("NAME", this->name).toString();
this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
if (settings.contains("BATTERY_SPECS"))
{
setBatterySpecs(settings.value("BATTERY_SPECS").toString());
}
settings.endGroup();
}
/**
* 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.
*/
void UAS::deleteSettings()
{
this->name = "";
this->airframe = QGC_AIRFRAME_GENERIC;
this->autopilot = -1;
setBatterySpecs(QString("9V,9.5V,12.6V"));
}
/**
* @ return the id of the uas
*/
int UAS::getUASID() const
{
return uasId;
}
/**
* Update the heartbeat.
*/
void UAS::updateState()
{
// Check if heartbeat timed out
quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
if (!connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
{
connectionLost = true;
QString audiostring = QString("Link lost to system %1").arg(this->getUASID());
GAudioOutput::instance()->say(audiostring.toLower());
}
// Update connection loss time on each iteration
if (connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
{
connectionLossTime = heartbeatInterval;
emit heartbeatTimeout(true, heartbeatInterval/1000);
}
// 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;
emit heartbeatTimeout(false, 0);
}
// Position lock is set by the MAVLink message handler
// if no position lock is available, indicate an error
if (positionLock)
{
positionLock = false;
}
else
{
if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock)
{
GAudioOutput::instance()->notifyNegative();
}
}
//#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);
}
/**
* 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.
*/
void UAS::setSelected()
{
if (UASManager::instance()->getActiveUAS() != this)
{
UASManager::instance()->setActiveUAS(this);
emit systemSelected(true);
}
}
/**
* @return if the active UAS is the current UAS
**/
bool UAS::getSelected() const
{
return (UASManager::instance()->getActiveUAS() == this);
}
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
if (!link) return;
if (!links->contains(link))
{
addLink(link);
// qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
}
if (!components.contains(message.compid))
{
QString componentName;
switch (message.compid)
{
case MAV_COMP_ID_ALL:
{
componentName = "ANONYMOUS";
break;
}
case MAV_COMP_ID_IMU:
{
componentName = "IMU #1";
break;
}
case MAV_COMP_ID_CAMERA:
{
componentName = "CAMERA";
break;
}
case MAV_COMP_ID_MISSIONPLANNER:
{
componentName = "MISSIONPLANNER";
break;
}
}
components.insert(message.compid, componentName);
emit componentCreated(uasId, message.compid, componentName);
}
// qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;
// 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))
{
QString uasState;
QString stateDescription;
bool multiComponentSourceDetected = false;
bool wrongComponent = false;
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;
}
// Store component ID
if (componentID[message.msgid] == -1)
{
// Prefer the first component
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;
switch (message.msgid)
{
case MAVLINK_MSG_ID_HEARTBEAT:
{
if (multiComponentSourceDetected && wrongComponent)
{
break;
}
lastHeartbeat = QGC::groundTimeUsecs();
emit heartbeat(this);
mavlink_heartbeat_t state;
mavlink_msg_heartbeat_decode(&message, &state);
// 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);
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);
// Set new type if it has changed
if (this->type != state.type)
{
this->type = state.type;
if (airframe == 0)
{
switch (type)
{
case MAV_TYPE_FIXED_WING:
setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
break;
case MAV_TYPE_QUADROTOR:
setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
break;
case MAV_TYPE_HEXAROTOR:
setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
break;
default:
// Do nothing
break;
}
}
this->autopilot = state.autopilot;
emit systemTypeSet(this, type);
}
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();
}
}
QString audiostring = QString("System %1").arg(uasId);
QString stateAudio = "";
QString modeAudio = "";
QString navModeAudio = "";
bool statechanged = false;
bool modechanged = false;
QString audiomodeText = getAudioModeTextFor(static_cast<int>(state.base_mode));
if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT)
{
statechanged = true;
this->status = state.system_status;
getStatusForCode((int)state.system_status, uasState, stateDescription);
emit statusChanged(this, uasState, stateDescription);
emit statusChanged(this->status);
shortStateText = uasState;
// 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;
}
if (this->mode != static_cast<int>(state.base_mode))
{
modechanged = true;
this->mode = static_cast<int>(state.base_mode);
shortModeText = getShortModeTextFor(this->mode);
emit modeChanged(this->getUASID(), shortModeText, "");
modeAudio = " is now in " + audiomodeText;
}
if (navMode != state.custom_mode)
{
emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
navMode = state.custom_mode;
//navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
}
// AUDIO
if (modechanged && statechanged)
{
// Output both messages
audiostring += modeAudio + " and " + stateAudio;
}
else if (modechanged || statechanged)
{
// Output the one message
audiostring += modeAudio + stateAudio + navModeAudio;
}
if (statechanged && ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY))
{
GAudioOutput::instance()->say(QString("emergency for system %1").arg(this->getUASID()));
QTimer::singleShot(3000, GAudioOutput::instance(), SLOT(startEmergency()));
}
else if (modechanged || statechanged)
{
GAudioOutput::instance()->stopEmergency();
GAudioOutput::instance()->say(audiostring.toLower());
}
}
break;
case MAVLINK_MSG_ID_SYS_STATUS:
{
if (multiComponentSourceDetected && wrongComponent)
{
break;
}
mavlink_sys_status_t state;
mavlink_msg_sys_status_decode(&message, &state);
// Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
quint64 time = getUnixTime();
QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid);
emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time);
emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time);
emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time);
emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time);
emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time);
emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time);
emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);
// Process CPU load.
emit loadChanged(this,state.load/10.0f);
emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
// Battery charge/time remaining/voltage calculations
currentVoltage = state.voltage_battery/1000.0f;
lpVoltage = filterVoltage(currentVoltage);
tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage;
// 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)
/* 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 */
&& ((currentVoltage - 0.2f) < tickVoltage)
/* warn only every 12 seconds */
&& (QGC::groundTimeUsecs() - lastVoltageWarning) > 12000000)
{
GAudioOutput::instance()->say(QString("voltage warning: %1 volts").arg(lpVoltage, 0, 'f', 1, QChar(' ')));
lastVoltageWarning = QGC::groundTimeUsecs();
lastTickVoltageValue = tickLowpassVoltage;
}
if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage;
timeRemaining = calculateTimeRemaining();
if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
{
chargeLevel = state.battery_remaining;
}
emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
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);
}
// LOW BATTERY ALARM
if (lpVoltage < warnVoltage && (currentVoltage - 0.2f) < warnVoltage && (currentVoltage > 3.3))
{
startLowBattAlarm();
}
else
{
stopLowBattAlarm();
}
// 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));
// 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)
{
state.drop_rate_comm = 10000;
}
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);
}
break;
case MAVLINK_MSG_ID_ATTITUDE:
{
mavlink_attitude_t attitude;
mavlink_msg_attitude_decode(&message, &attitude);
quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
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);
}
}
break;
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;
case MAVLINK_MSG_ID_HIL_CONTROLS:
{
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);
}
break;
case MAVLINK_MSG_ID_VFR_HUD:
{
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);
if (!attitudeKnown)
{
yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
emit attitudeChanged(this, roll, pitch, yaw, time);
}
emit altitudeChanged(uasId, hud.alt);
emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
}
break;
case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
//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;
{
mavlink_local_position_ned_t pos;
mavlink_msg_local_position_ned_decode(&message, &pos);
quint64 time = getUnixTime(pos.time_boot_ms);
// Emit position always with component ID
emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time);
if (!wrongComponent)
{
localX = pos.x;
localY = pos.y;
localZ = pos.z;
// Emit
emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
// Set internal state
if (!positionLock) {
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
isLocalPositionKnown = true;
}
}
break;
case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
{
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);
}
break;
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
//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;
{
mavlink_global_position_int_t pos;
mavlink_msg_global_position_int_decode(&message, &pos);
quint64 time = getUnixTime();
Michael Carpenter
committed
//latitude = pos.lat/(double)1E7;
setLatitude(pos.lat/(double)1E7);
//longitude = pos.lon/(double)1E7;
setLongitude(pos.lon/(double)1E7);
//altitude = pos.alt/1000.0;
setAltitude(pos.alt/1000.0);
globalEstimatorActive = true;
speedX = pos.vx/100.0;
speedY = pos.vy/100.0;
speedZ = pos.vz/100.0;
Michael Carpenter
committed
emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitude(), time);
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
emit speedChanged(this, speedX, speedY, speedZ, time);
// Set internal state
if (!positionLock)
{
// 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);
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);
if (pos.fix_type > 2)
{
latitude_gps = pos.lat/(double)1E7;
longitude_gps = pos.lon/(double)1E7;
altitude_gps = pos.alt/1000.0;
if (!globalEstimatorActive) {
Michael Carpenter
committed
//latitude = latitude_gps;
setLatitude(latitude_gps);
//longitude = longitude_gps;
setLongitude(longitude_gps);
//altitude = altitude_gps;
setAltitude(altitude_gps);
emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitude(), time);
positionLock = true;
isGlobalPositionKnown = true;
// Smaller than threshold and not NaN
float vel = pos.vel/100.0f;
if (!globalEstimatorActive) {
if ((vel < 1000000) && !isnan(vel) && !isinf(vel))
{
emit speedChanged(this, vel, 0.0, 0.0, time);
}
else
{
emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
}
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
}
}
}
break;
case MAVLINK_MSG_ID_GPS_STATUS:
{
mavlink_gps_status_t pos;
mavlink_msg_gps_status_decode(&message, &pos);
for(int i = 0; i < (int)pos.satellites_visible; i++)
{
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]));
}
}
break;
case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
{
mavlink_gps_global_origin_t pos;
mavlink_msg_gps_global_origin_decode(&message, &pos);
emit homePositionChanged(uasId, pos.latitude / 10000000.0, pos.longitude / 10000000.0, pos.altitude / 1000.0);
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
{
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);
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
{
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);
}
break;
case MAVLINK_MSG_ID_PARAM_VALUE:
{
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);
// 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);
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))
{
parameters.insert(component, new QMap<QString, QVariant>());
}
// Insert parameter into registry
if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
// Insert with correct type
// TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling.
switch (value.param_type)
{
case MAV_PARAM_TYPE_REAL32:
{
// Variant
Michael Carpenter
committed
QVariant param;
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
param = QVariant(val.param_float);
}
else
{
param = QVariant(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;
}
break;
case MAV_PARAM_TYPE_UINT8:
{
// Variant
Michael Carpenter
committed
QVariant param;
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
param = QVariant(QChar((unsigned char)val.param_float));
}
else
{
param = QVariant(QChar((unsigned char)val.param_uint8));
}
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;
}
Michael Carpenter
committed
break;
case MAV_PARAM_TYPE_INT8:
{
// Variant
Michael Carpenter
committed
QVariant param;
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
param = QVariant(QChar((char)val.param_float));
}
else
{
param = QVariant(QChar((char)val.param_int8));
}
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;
}
Michael Carpenter
committed
break;
case MAV_PARAM_TYPE_INT16:
{
// Variant
Michael Carpenter
committed
QVariant param;
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
param = QVariant((short)val.param_float);
}
else
{
param = QVariant(val.param_int16);
}
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;
}
Michael Carpenter
committed
break;
case MAV_PARAM_TYPE_UINT32:
{
// Variant
Michael Carpenter
committed
QVariant param;
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
param = QVariant((unsigned int)val.param_float);
}
else
{
param = QVariant(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);
}
break;
case MAV_PARAM_TYPE_INT32:
{
// Variant
Michael Carpenter
committed
QVariant param;
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
param = QVariant((int)val.param_float);
}
else
{
param = QVariant(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;