-
Notifications
You must be signed in to change notification settings - Fork 3.8k
/
Copy pathVehicle.cc
3258 lines (2844 loc) · 118 KB
/
Vehicle.cc
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
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
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
737
738
739
740
741
742
743
744
745
746
747
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
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
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
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include <QTime>
#include <QDateTime>
#include <QLocale>
#include "Vehicle.h"
#include "MAVLinkProtocol.h"
#include "FirmwarePluginManager.h"
#include "LinkManager.h"
#include "FirmwarePlugin.h"
#include "UAS.h"
#include "JoystickManager.h"
#include "MissionManager.h"
#include "MissionController.h"
#include "PlanMasterController.h"
#include "GeoFenceManager.h"
#include "RallyPointManager.h"
#include "CoordinateVector.h"
#include "ParameterManager.h"
#include "QGCApplication.h"
#include "QGCImageProvider.h"
#include "AudioOutput.h"
#include "FollowMe.h"
#include "MissionCommandTree.h"
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
#include "QGCQGeoCoordinate.h"
#include "QGCCorePlugin.h"
#include "ADSBVehicle.h"
#include "QGCCameraManager.h"
#include "VideoReceiver.h"
#include "VideoManager.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
#define UPDATE_TIMER 50
#define DEFAULT_LAT 38.965767f
#define DEFAULT_LON -120.083923f
const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle.");
const char* Vehicle::_settingsGroup = "Vehicle%1"; // %1 replaced with mavlink system id
const char* Vehicle::_joystickModeSettingsKey = "JoystickMode";
const char* Vehicle::_joystickEnabledSettingsKey = "JoystickEnabled";
const char* Vehicle::_rollFactName = "roll";
const char* Vehicle::_pitchFactName = "pitch";
const char* Vehicle::_headingFactName = "heading";
const char* Vehicle::_airSpeedFactName = "airSpeed";
const char* Vehicle::_groundSpeedFactName = "groundSpeed";
const char* Vehicle::_climbRateFactName = "climbRate";
const char* Vehicle::_altitudeRelativeFactName = "altitudeRelative";
const char* Vehicle::_altitudeAMSLFactName = "altitudeAMSL";
const char* Vehicle::_flightDistanceFactName = "flightDistance";
const char* Vehicle::_flightTimeFactName = "flightTime";
const char* Vehicle::_distanceToHomeFactName = "distanceToHome";
const char* Vehicle::_hobbsFactName = "hobbs";
const char* Vehicle::_gpsFactGroupName = "gps";
const char* Vehicle::_batteryFactGroupName = "battery";
const char* Vehicle::_windFactGroupName = "wind";
const char* Vehicle::_vibrationFactGroupName = "vibration";
const char* Vehicle::_temperatureFactGroupName = "temperature";
const char* Vehicle::_clockFactGroupName = "clock";
Vehicle::Vehicle(LinkInterface* link,
int vehicleId,
int defaultComponentId,
MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager,
JoystickManager* joystickManager)
: FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json")
, _id(vehicleId)
, _defaultComponentId(defaultComponentId)
, _active(false)
, _offlineEditingVehicle(false)
, _firmwareType(firmwareType)
, _vehicleType(vehicleType)
, _firmwarePlugin(NULL)
, _firmwarePluginInstanceData(NULL)
, _autopilotPlugin(NULL)
, _mavlink(NULL)
, _soloFirmware(false)
, _toolbox(qgcApp()->toolbox())
, _settingsManager(_toolbox->settingsManager())
, _joystickMode(JoystickModeRC)
, _joystickEnabled(false)
, _uas(NULL)
, _mav(NULL)
, _currentMessageCount(0)
, _messageCount(0)
, _currentErrorCount(0)
, _currentWarningCount(0)
, _currentNormalCount(0)
, _currentMessageType(MessageNone)
, _updateCount(0)
, _rcRSSI(255)
, _rcRSSIstore(255)
, _autoDisconnect(false)
, _flying(false)
, _landing(false)
, _vtolInFwdFlight(false)
, _onboardControlSensorsPresent(0)
, _onboardControlSensorsEnabled(0)
, _onboardControlSensorsHealth(0)
, _onboardControlSensorsUnhealthy(0)
, _gpsRawIntMessageAvailable(false)
, _globalPositionIntMessageAvailable(false)
, _defaultCruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
, _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
, _telemetryRRSSI(0)
, _telemetryLRSSI(0)
, _telemetryRXErrors(0)
, _telemetryFixed(0)
, _telemetryTXBuffer(0)
, _telemetryLNoise(0)
, _telemetryRNoise(0)
, _maxProtoVersion(0)
, _vehicleCapabilitiesKnown(false)
, _capabilityBits(0)
, _highLatencyLink(false)
, _cameras(NULL)
, _connectionLost(false)
, _connectionLostEnabled(true)
, _initialPlanRequestComplete(false)
, _missionManager(NULL)
, _missionManagerInitialRequestSent(false)
, _geoFenceManager(NULL)
, _geoFenceManagerInitialRequestSent(false)
, _rallyPointManager(NULL)
, _rallyPointManagerInitialRequestSent(false)
, _parameterManager(NULL)
, _armed(false)
, _base_mode(0)
, _custom_mode(0)
, _nextSendMessageMultipleIndex(0)
, _firmwarePluginManager(firmwarePluginManager)
, _joystickManager(joystickManager)
, _flowImageIndex(0)
, _allLinksInactiveSent(false)
, _messagesReceived(0)
, _messagesSent(0)
, _messagesLost(0)
, _messageSeq(0)
, _compID(0)
, _heardFrom(false)
, _firmwareMajorVersion(versionNotSetValue)
, _firmwareMinorVersion(versionNotSetValue)
, _firmwarePatchVersion(versionNotSetValue)
, _firmwareCustomMajorVersion(versionNotSetValue)
, _firmwareCustomMinorVersion(versionNotSetValue)
, _firmwareCustomPatchVersion(versionNotSetValue)
, _firmwareVersionType(FIRMWARE_VERSION_TYPE_OFFICIAL)
, _gitHash(versionNotSetValue)
, _uid(0)
, _lastAnnouncedLowBatteryPercent(100)
, _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble)
, _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble)
, _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble)
, _groundSpeedFact (0, _groundSpeedFactName, FactMetaData::valueTypeDouble)
, _airSpeedFact (0, _airSpeedFactName, FactMetaData::valueTypeDouble)
, _climbRateFact (0, _climbRateFactName, FactMetaData::valueTypeDouble)
, _altitudeRelativeFact (0, _altitudeRelativeFactName, FactMetaData::valueTypeDouble)
, _altitudeAMSLFact (0, _altitudeAMSLFactName, FactMetaData::valueTypeDouble)
, _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble)
, _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds)
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
, _gpsFactGroup(this)
, _batteryFactGroup(this)
, _windFactGroup(this)
, _vibrationFactGroup(this)
, _temperatureFactGroup(this)
, _clockFactGroup(this)
{
_addLink(link);
connect(_joystickManager, &JoystickManager::activeJoystickChanged, this, &Vehicle::_loadSettings);
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleAvailableChanged, this, &Vehicle::_loadSettings);
_mavlink = _toolbox->mavlinkProtocol();
connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
connect(this, &Vehicle::_sendMessageOnLinkOnThread, this, &Vehicle::_sendMessageOnLink, Qt::QueuedConnection);
connect(this, &Vehicle::flightModeChanged, this, &Vehicle::_handleFlightModeChanged);
connect(this, &Vehicle::armedChanged, this, &Vehicle::_announceArmedChanged);
connect(_toolbox->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &Vehicle::_vehicleParamLoaded);
_uas = new UAS(_mavlink, this, _firmwarePluginManager);
connect(_uas, &UAS::imageReady, this, &Vehicle::_imageReady);
connect(this, &Vehicle::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged);
_commonInit();
_autopilotPlugin = _firmwarePlugin->autopilotPlugin(this);
// connect this vehicle to the follow me handle manager
connect(this, &Vehicle::flightModeChanged,_toolbox->followMe(), &FollowMe::followMeHandleManager);
// PreArm Error self-destruct timer
connect(&_prearmErrorTimer, &QTimer::timeout, this, &Vehicle::_prearmErrorTimeout);
_prearmErrorTimer.setInterval(_prearmErrorTimeoutMSecs);
_prearmErrorTimer.setSingleShot(true);
// Connection Lost timer
_connectionLostTimer.setInterval(_connectionLostTimeoutMSecs);
_connectionLostTimer.setSingleShot(false);
_connectionLostTimer.start();
connect(&_connectionLostTimer, &QTimer::timeout, this, &Vehicle::_connectionLostTimeout);
// Send MAV_CMD ack timer
_mavCommandAckTimer.setSingleShot(true);
_mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
connect(&_mavCommandAckTimer, &QTimer::timeout, this, &Vehicle::_sendMavCommandAgain);
_mav = uas();
// Listen for system messages
connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage);
connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageReceived, this, &Vehicle::_handletextMessageReceived);
// Now connect the new UAS
connect(_mav, SIGNAL(attitudeChanged (UASInterface*,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64)));
connect(_mav, SIGNAL(attitudeChanged (UASInterface*,int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64)));
if (_highLatencyLink) {
// High latency links don't request information
_setMaxProtoVersion(100);
_setCapabilities(0);
_initialPlanRequestComplete = true;
_missionManagerInitialRequestSent = true;
_geoFenceManagerInitialRequestSent = true;
_rallyPointManagerInitialRequestSent = true;
} else {
// Ask the vehicle for protocol version info.
sendMavCommand(MAV_COMP_ID_ALL, // Don't know default component id yet.
MAV_CMD_REQUEST_PROTOCOL_VERSION,
false, // No error shown if fails
1); // Request protocol version
// Ask the vehicle for firmware version info.
sendMavCommand(MAV_COMP_ID_ALL, // Don't know default component id yet.
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
false, // No error shown if fails
1); // Request firmware version
}
_firmwarePlugin->initializeVehicle(this);
_sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay);
connect(&_sendMultipleTimer, &QTimer::timeout, this, &Vehicle::_sendMessageMultipleNext);
_mapTrajectoryTimer.setInterval(_mapTrajectoryMsecsBetweenPoints);
connect(&_mapTrajectoryTimer, &QTimer::timeout, this, &Vehicle::_addNewMapTrajectoryPoint);
// Create camera manager instance
_cameras = _firmwarePlugin->createCameraManager(this);
emit dynamicCamerasChanged();
}
// Disconnected Vehicle for offline editing
Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager,
QObject* parent)
: FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json", parent)
, _id(0)
, _defaultComponentId(MAV_COMP_ID_ALL)
, _active(false)
, _offlineEditingVehicle(true)
, _firmwareType(firmwareType)
, _vehicleType(vehicleType)
, _firmwarePlugin(NULL)
, _firmwarePluginInstanceData(NULL)
, _autopilotPlugin(NULL)
, _mavlink(NULL)
, _soloFirmware(false)
, _toolbox(qgcApp()->toolbox())
, _settingsManager(_toolbox->settingsManager())
, _joystickMode(JoystickModeRC)
, _joystickEnabled(false)
, _uas(NULL)
, _mav(NULL)
, _currentMessageCount(0)
, _messageCount(0)
, _currentErrorCount(0)
, _currentWarningCount(0)
, _currentNormalCount(0)
, _currentMessageType(MessageNone)
, _updateCount(0)
, _rcRSSI(255)
, _rcRSSIstore(255)
, _autoDisconnect(false)
, _flying(false)
, _landing(false)
, _vtolInFwdFlight(false)
, _onboardControlSensorsPresent(0)
, _onboardControlSensorsEnabled(0)
, _onboardControlSensorsHealth(0)
, _onboardControlSensorsUnhealthy(0)
, _gpsRawIntMessageAvailable(false)
, _globalPositionIntMessageAvailable(false)
, _defaultCruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
, _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
, _vehicleCapabilitiesKnown(true)
, _capabilityBits(_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY)
, _highLatencyLink(false)
, _cameras(NULL)
, _connectionLost(false)
, _connectionLostEnabled(true)
, _initialPlanRequestComplete(false)
, _missionManager(NULL)
, _missionManagerInitialRequestSent(false)
, _geoFenceManager(NULL)
, _geoFenceManagerInitialRequestSent(false)
, _rallyPointManager(NULL)
, _rallyPointManagerInitialRequestSent(false)
, _parameterManager(NULL)
, _armed(false)
, _base_mode(0)
, _custom_mode(0)
, _nextSendMessageMultipleIndex(0)
, _firmwarePluginManager(firmwarePluginManager)
, _joystickManager(NULL)
, _flowImageIndex(0)
, _allLinksInactiveSent(false)
, _messagesReceived(0)
, _messagesSent(0)
, _messagesLost(0)
, _messageSeq(0)
, _compID(0)
, _heardFrom(false)
, _firmwareMajorVersion(versionNotSetValue)
, _firmwareMinorVersion(versionNotSetValue)
, _firmwarePatchVersion(versionNotSetValue)
, _firmwareCustomMajorVersion(versionNotSetValue)
, _firmwareCustomMinorVersion(versionNotSetValue)
, _firmwareCustomPatchVersion(versionNotSetValue)
, _firmwareVersionType(FIRMWARE_VERSION_TYPE_OFFICIAL)
, _gitHash(versionNotSetValue)
, _uid(0)
, _lastAnnouncedLowBatteryPercent(100)
, _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble)
, _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble)
, _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble)
, _groundSpeedFact (0, _groundSpeedFactName, FactMetaData::valueTypeDouble)
, _airSpeedFact (0, _airSpeedFactName, FactMetaData::valueTypeDouble)
, _climbRateFact (0, _climbRateFactName, FactMetaData::valueTypeDouble)
, _altitudeRelativeFact (0, _altitudeRelativeFactName, FactMetaData::valueTypeDouble)
, _altitudeAMSLFact (0, _altitudeAMSLFactName, FactMetaData::valueTypeDouble)
, _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble)
, _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds)
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
, _gpsFactGroup(this)
, _batteryFactGroup(this)
, _windFactGroup(this)
, _vibrationFactGroup(this)
, _clockFactGroup(this)
{
_commonInit();
_firmwarePlugin->initializeVehicle(this);
}
void Vehicle::_commonInit(void)
{
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
connect(_firmwarePlugin, &FirmwarePlugin::toolbarIndicatorsChanged, this, &Vehicle::toolBarIndicatorsChanged);
connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceToHome);
connect(this, &Vehicle::homePositionChanged, this, &Vehicle::_updateDistanceToHome);
connect(this, &Vehicle::hobbsMeterChanged, this, &Vehicle::_updateHobbsMeter);
_missionManager = new MissionManager(this);
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_missionLoadComplete);
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearCameraTriggerPoints);
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearTrajectoryPoints);
connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearCameraTriggerPoints);
connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearTrajectoryPoints);
_parameterManager = new ParameterManager(this);
connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
// GeoFenceManager needs to access ParameterManager so make sure to create after
_geoFenceManager = new GeoFenceManager(this);
connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
connect(_geoFenceManager, &GeoFenceManager::loadComplete, this, &Vehicle::_geoFenceLoadComplete);
_rallyPointManager = new RallyPointManager(this);
connect(_rallyPointManager, &RallyPointManager::error, this, &Vehicle::_rallyPointManagerError);
connect(_rallyPointManager, &RallyPointManager::loadComplete, this, &Vehicle::_rallyPointLoadComplete);
// Offline editing vehicle tracks settings changes for offline editing settings
connect(_settingsManager->appSettings()->offlineEditingFirmwareType(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
connect(_settingsManager->appSettings()->offlineEditingVehicleType(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
connect(_settingsManager->appSettings()->offlineEditingCruiseSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineCruiseSpeedSettingChanged);
connect(_settingsManager->appSettings()->offlineEditingHoverSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineHoverSpeedSettingChanged);
// Build FactGroup object model
_addFact(&_rollFact, _rollFactName);
_addFact(&_pitchFact, _pitchFactName);
_addFact(&_headingFact, _headingFactName);
_addFact(&_groundSpeedFact, _groundSpeedFactName);
_addFact(&_airSpeedFact, _airSpeedFactName);
_addFact(&_climbRateFact, _climbRateFactName);
_addFact(&_altitudeRelativeFact, _altitudeRelativeFactName);
_addFact(&_altitudeAMSLFact, _altitudeAMSLFactName);
_addFact(&_flightDistanceFact, _flightDistanceFactName);
_addFact(&_flightTimeFact, _flightTimeFactName);
_addFact(&_distanceToHomeFact, _distanceToHomeFactName);
_hobbsFact.setRawValue(QVariant(QString("0000:00:00")));
_addFact(&_hobbsFact, _hobbsFactName);
_addFactGroup(&_gpsFactGroup, _gpsFactGroupName);
_addFactGroup(&_batteryFactGroup, _batteryFactGroupName);
_addFactGroup(&_windFactGroup, _windFactGroupName);
_addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName);
_addFactGroup(&_temperatureFactGroup, _temperatureFactGroupName);
_addFactGroup(&_clockFactGroup, _clockFactGroupName);
// Add firmware-specific fact groups, if provided
QMap<QString, FactGroup*>* fwFactGroups = _firmwarePlugin->factGroups();
if (fwFactGroups) {
QMapIterator<QString, FactGroup*> i(*fwFactGroups);
while(i.hasNext()) {
i.next();
_addFactGroup(i.value(), i.key());
}
}
_flightDistanceFact.setRawValue(0);
_flightTimeFact.setRawValue(0);
}
Vehicle::~Vehicle()
{
qCDebug(VehicleLog) << "~Vehicle" << this;
delete _missionManager;
_missionManager = NULL;
delete _autopilotPlugin;
_autopilotPlugin = NULL;
delete _mav;
_mav = NULL;
}
void Vehicle::prepareDelete()
{
if(_cameras) {
delete _cameras;
_cameras = NULL;
emit dynamicCamerasChanged();
qApp->processEvents();
}
}
void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value)
{
_firmwareType = static_cast<MAV_AUTOPILOT>(value.toInt());
emit firmwareTypeChanged();
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
_capabilityBits = 0;
} else {
_capabilityBits = MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY;
}
emit capabilityBitsChanged(_capabilityBits);
}
void Vehicle::_offlineVehicleTypeSettingChanged(QVariant value)
{
_vehicleType = static_cast<MAV_TYPE>(value.toInt());
emit vehicleTypeChanged();
}
void Vehicle::_offlineCruiseSpeedSettingChanged(QVariant value)
{
_defaultCruiseSpeed = value.toDouble();
emit defaultCruiseSpeedChanged(_defaultCruiseSpeed);
}
void Vehicle::_offlineHoverSpeedSettingChanged(QVariant value)
{
_defaultHoverSpeed = value.toDouble();
emit defaultHoverSpeedChanged(_defaultHoverSpeed);
}
QString Vehicle::firmwareTypeString(void) const
{
if (px4Firmware()) {
return QStringLiteral("PX4 Pro");
} else if (apmFirmware()) {
return QStringLiteral("ArduPilot");
} else {
return tr("MAVLink Generic");
}
}
QString Vehicle::vehicleTypeString(void) const
{
if (fixedWing()) {
return tr("Fixed Wing");
} else if (multiRotor()) {
return tr("Multi-Rotor");
} else if (vtol()) {
return tr("VTOL");
} else if (rover()) {
return tr("Rover");
} else if (sub()) {
return tr("Sub");
} else {
return tr("Unknown");
}
}
void Vehicle::resetCounters()
{
_messagesReceived = 0;
_messagesSent = 0;
_messagesLost = 0;
_messageSeq = 0;
_heardFrom = false;
}
void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message)
{
// if the minimum supported version of MAVLink is already 2.0
// set our max proto version to it.
unsigned mavlinkVersion = _mavlink->getCurrentVersion();
if (_maxProtoVersion != mavlinkVersion && mavlinkVersion >= 200) {
_maxProtoVersion = _mavlink->getCurrentVersion();
qCDebug(VehicleLog) << "Vehicle::_mavlinkMessageReceived setting _maxProtoVersion" << _maxProtoVersion;
}
if (message.sysid != _id && message.sysid != 0) {
// We allow RADIO_STATUS messages which come from a link the vehicle is using to pass through and be handled
if (!(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS && _containsLink(link))) {
return;
}
}
if (!_containsLink(link)) {
_addLink(link);
}
//-- Check link status
_messagesReceived++;
emit messagesReceivedChanged();
if(!_heardFrom) {
if(message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
_heardFrom = true;
_compID = message.compid;
_messageSeq = message.seq + 1;
}
} else {
if(_compID == message.compid) {
uint16_t seq_received = (uint16_t)message.seq;
uint16_t packet_lost_count = 0;
//-- Account for overflow during packet loss
if(seq_received < _messageSeq) {
packet_lost_count = (seq_received + 255) - _messageSeq;
} else {
packet_lost_count = seq_received - _messageSeq;
}
_messageSeq = message.seq + 1;
_messagesLost += packet_lost_count;
if(packet_lost_count)
emit messagesLostChanged();
}
}
// Mark this vehicle as active - but only if the traffic is coming from
// the actual vehicle
if (message.sysid == _id) {
_connectionActive();
}
// Give the plugin a change to adjust the message contents
if (!_firmwarePlugin->adjustIncomingMavlinkMessage(this, &message)) {
return;
}
// Give the Core Plugin access to all mavlink traffic
if (!_toolbox->corePlugin()->mavlinkMessage(this, link, message)) {
return;
}
switch (message.msgid) {
case MAVLINK_MSG_ID_HOME_POSITION:
_handleHomePosition(message);
break;
case MAVLINK_MSG_ID_HEARTBEAT:
_handleHeartbeat(message);
break;
case MAVLINK_MSG_ID_RADIO_STATUS:
_handleRadioStatus(message);
break;
case MAVLINK_MSG_ID_RC_CHANNELS:
_handleRCChannels(message);
break;
case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
_handleRCChannelsRaw(message);
break;
case MAVLINK_MSG_ID_BATTERY_STATUS:
_handleBatteryStatus(message);
break;
case MAVLINK_MSG_ID_SYS_STATUS:
_handleSysStatus(message);
break;
case MAVLINK_MSG_ID_RAW_IMU:
emit mavlinkRawImu(message);
break;
case MAVLINK_MSG_ID_SCALED_IMU:
emit mavlinkScaledImu1(message);
break;
case MAVLINK_MSG_ID_SCALED_IMU2:
emit mavlinkScaledImu2(message);
break;
case MAVLINK_MSG_ID_SCALED_IMU3:
emit mavlinkScaledImu3(message);
break;
case MAVLINK_MSG_ID_VIBRATION:
_handleVibration(message);
break;
case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
_handleExtendedSysState(message);
break;
case MAVLINK_MSG_ID_COMMAND_ACK:
_handleCommandAck(message);
break;
case MAVLINK_MSG_ID_COMMAND_LONG:
_handleCommandLong(message);
break;
case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
_handleAutopilotVersion(link, message);
break;
case MAVLINK_MSG_ID_PROTOCOL_VERSION:
_handleProtocolVersion(link, message);
break;
case MAVLINK_MSG_ID_WIND_COV:
_handleWindCov(message);
break;
case MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS:
_handleHilActuatorControls(message);
break;
case MAVLINK_MSG_ID_LOGGING_DATA:
_handleMavlinkLoggingData(message);
break;
case MAVLINK_MSG_ID_LOGGING_DATA_ACKED:
_handleMavlinkLoggingDataAcked(message);
break;
case MAVLINK_MSG_ID_GPS_RAW_INT:
_handleGpsRawInt(message);
break;
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
_handleGlobalPositionInt(message);
break;
case MAVLINK_MSG_ID_ALTITUDE:
_handleAltitude(message);
break;
case MAVLINK_MSG_ID_VFR_HUD:
_handleVfrHud(message);
break;
case MAVLINK_MSG_ID_SCALED_PRESSURE:
_handleScaledPressure(message);
break;
case MAVLINK_MSG_ID_SCALED_PRESSURE2:
_handleScaledPressure2(message);
break;
case MAVLINK_MSG_ID_SCALED_PRESSURE3:
_handleScaledPressure3(message);
break;
case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
_handleCameraImageCaptured(message);
break;
case MAVLINK_MSG_ID_ADSB_VEHICLE:
_handleADSBVehicle(message);
break;
case MAVLINK_MSG_ID_HIGH_LATENCY2:
_handleHighLatency2(message);
break;
case MAVLINK_MSG_ID_SERIAL_CONTROL:
{
mavlink_serial_control_t ser;
mavlink_msg_serial_control_decode(&message, &ser);
emit mavlinkSerialControl(ser.device, ser.flags, ser.timeout, ser.baudrate, QByteArray(reinterpret_cast<const char*>(ser.data), ser.count));
}
break;
// Following are ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
_handleCameraFeedback(message);
break;
case MAVLINK_MSG_ID_WIND:
_handleWind(message);
break;
#endif
}
// This must be emitted after the vehicle processes the message. This way the vehicle state is up to date when anyone else
// does processing.
emit mavlinkMessageReceived(message);
_uas->receiveMessage(message);
}
#if !defined(NO_ARDUPILOT_DIALECT)
void Vehicle::_handleCameraFeedback(const mavlink_message_t& message)
{
mavlink_camera_feedback_t feedback;
mavlink_msg_camera_feedback_decode(&message, &feedback);
QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lng / qPow(10.0, 7.0), feedback.alt_msl);
qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx;
_cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
}
#endif
void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message)
{
mavlink_camera_image_captured_t feedback;
mavlink_msg_camera_image_captured_decode(&message, &feedback);
QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lon / qPow(10.0, 7.0), feedback.alt);
qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.image_index << feedback.capture_result;
if (feedback.capture_result == 1) {
_cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
}
}
void Vehicle::_handleVfrHud(mavlink_message_t& message)
{
mavlink_vfr_hud_t vfrHud;
mavlink_msg_vfr_hud_decode(&message, &vfrHud);
_airSpeedFact.setRawValue(qIsNaN(vfrHud.airspeed) ? 0 : vfrHud.airspeed);
_groundSpeedFact.setRawValue(qIsNaN(vfrHud.groundspeed) ? 0 : vfrHud.groundspeed);
_climbRateFact.setRawValue(qIsNaN(vfrHud.climb) ? 0 : vfrHud.climb);
}
void Vehicle::_handleGpsRawInt(mavlink_message_t& message)
{
mavlink_gps_raw_int_t gpsRawInt;
mavlink_msg_gps_raw_int_decode(&message, &gpsRawInt);
_gpsRawIntMessageAvailable = true;
if (gpsRawInt.fix_type >= GPS_FIX_TYPE_3D_FIX) {
if (!_globalPositionIntMessageAvailable) {
//-- Set these here and emit a single signal instead of 3 for the same variable (_coordinate)
_coordinate.setLatitude(gpsRawInt.lat / (double)1E7);
_coordinate.setLongitude(gpsRawInt.lon / (double)1E7);
_coordinate.setAltitude(gpsRawInt.alt / 1000.0);
emit coordinateChanged(_coordinate);
_altitudeAMSLFact.setRawValue(gpsRawInt.alt / 1000.0);
}
}
_gpsFactGroup.lat()->setRawValue(gpsRawInt.lat * 1e-7);
_gpsFactGroup.lon()->setRawValue(gpsRawInt.lon * 1e-7);
_gpsFactGroup.count()->setRawValue(gpsRawInt.satellites_visible == 255 ? 0 : gpsRawInt.satellites_visible);
_gpsFactGroup.hdop()->setRawValue(gpsRawInt.eph == UINT16_MAX ? std::numeric_limits<double>::quiet_NaN() : gpsRawInt.eph / 100.0);
_gpsFactGroup.vdop()->setRawValue(gpsRawInt.epv == UINT16_MAX ? std::numeric_limits<double>::quiet_NaN() : gpsRawInt.epv / 100.0);
_gpsFactGroup.courseOverGround()->setRawValue(gpsRawInt.cog == UINT16_MAX ? std::numeric_limits<double>::quiet_NaN() : gpsRawInt.cog / 100.0);
_gpsFactGroup.lock()->setRawValue(gpsRawInt.fix_type);
}
void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
{
mavlink_global_position_int_t globalPositionInt;
mavlink_msg_global_position_int_decode(&message, &globalPositionInt);
_altitudeRelativeFact.setRawValue(globalPositionInt.relative_alt / 1000.0);
_altitudeAMSLFact.setRawValue(globalPositionInt.alt / 1000.0);
// ArduPilot sends bogus GLOBAL_POSITION_INT messages with lat/lat 0/0 even when it has no gps signal
// Apparently, this is in order to transport relative altitude information.
if (globalPositionInt.lat == 0 && globalPositionInt.lon == 0) {
return;
}
_globalPositionIntMessageAvailable = true;
//-- Set these here and emit a single signal instead of 3 for the same variable (_coordinate)
_coordinate.setLatitude(globalPositionInt.lat / (double)1E7);
_coordinate.setLongitude(globalPositionInt.lon / (double)1E7);
_coordinate.setAltitude(globalPositionInt.alt / 1000.0);
emit coordinateChanged(_coordinate);
}
void Vehicle::_handleHighLatency2(mavlink_message_t& message)
{
mavlink_high_latency2_t highLatency2;
mavlink_msg_high_latency2_decode(&message, &highLatency2);
QString previousFlightMode;
if (_base_mode != 0 || _custom_mode != 0){
// Vehicle is initialized with _base_mode=0 and _custom_mode=0. Don't pass this to flightMode() since it will complain about
// bad modes while unit testing.
previousFlightMode = flightMode();
}
_base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
_custom_mode = _firmwarePlugin->highLatencyCustomModeTo32Bits(highLatency2.custom_mode);
if (previousFlightMode != flightMode()) {
emit flightModeChanged(flightMode());
}
// Assume armed since we don't know
if (_armed != true) {
_armed = true;
emit armedChanged(_armed);
}
_coordinate.setLatitude(highLatency2.latitude / (double)1E7);
_coordinate.setLongitude(highLatency2.longitude / (double)1E7);
_coordinate.setAltitude(highLatency2.altitude);
emit coordinateChanged(_coordinate);
_airSpeedFact.setRawValue((double)highLatency2.airspeed / 5.0);
_groundSpeedFact.setRawValue((double)highLatency2.groundspeed / 5.0);
_climbRateFact.setRawValue((double)highLatency2.climb_rate / 10.0);
_headingFact.setRawValue((double)highLatency2.heading * 2.0);
_altitudeRelativeFact.setRawValue(std::numeric_limits<double>::quiet_NaN());
_altitudeAMSLFact.setRawValue(highLatency2.altitude);
_windFactGroup.direction()->setRawValue((double)highLatency2.wind_heading * 2.0);
_windFactGroup.speed()->setRawValue((double)highLatency2.windspeed / 5.0);
_batteryFactGroup.percentRemaining()->setRawValue(highLatency2.battery);
_temperatureFactGroup.temperature1()->setRawValue(highLatency2.temperature_air);
_gpsFactGroup.lat()->setRawValue(highLatency2.latitude * 1e-7);
_gpsFactGroup.lon()->setRawValue(highLatency2.longitude * 1e-7);
_gpsFactGroup.count()->setRawValue(0);
_gpsFactGroup.hdop()->setRawValue(highLatency2.eph == UINT8_MAX ? std::numeric_limits<double>::quiet_NaN() : highLatency2.eph / 10.0);
_gpsFactGroup.vdop()->setRawValue(highLatency2.epv == UINT8_MAX ? std::numeric_limits<double>::quiet_NaN() : highLatency2.epv / 10.0);
struct failure2Sensor_s {
HL_FAILURE_FLAG failureBit;
MAV_SYS_STATUS_SENSOR sensorBit;
};
static const failure2Sensor_s rgFailure2Sensor[] = {
{ HL_FAILURE_FLAG_GPS, MAV_SYS_STATUS_SENSOR_GPS },
{ HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE, MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE },
{ HL_FAILURE_FLAG_ABSOLUTE_PRESSURE, MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE },
{ HL_FAILURE_FLAG_3D_ACCEL, MAV_SYS_STATUS_SENSOR_3D_ACCEL },
{ HL_FAILURE_FLAG_3D_GYRO, MAV_SYS_STATUS_SENSOR_3D_GYRO },
{ HL_FAILURE_FLAG_3D_MAG, MAV_SYS_STATUS_SENSOR_3D_MAG },
#if 0
// FIXME: These don't currently map to existing sensor health bits. Support needs to be added to show them
// on health page of instrument panel as well.
{ HL_FAILURE_FLAG_TERRAIN=64, /* Terrain subsystem failure. | */
{ HL_FAILURE_FLAG_BATTERY=128, /* Battery failure/critical low battery. | */
{ HL_FAILURE_FLAG_RC_RECEIVER=256, /* RC receiver failure/no rc connection. | */
{ HL_FAILURE_FLAG_OFFBOARD_LINK=512, /* Offboard link failure. | */
{ HL_FAILURE_FLAG_ENGINE=1024, /* Engine failure. | */
{ HL_FAILURE_FLAG_GEOFENCE=2048, /* Geofence violation. | */
{ HL_FAILURE_FLAG_ESTIMATOR=4096, /* Estimator failure, for example measurement rejection or large variances. | */
{ HL_FAILURE_FLAG_MISSION=8192, /* Mission failure. | */
#endif
};
// Map from MAV_FAILURE bits to standard SYS_STATUS message handling
uint32_t newOnboardControlSensorsEnabled = 0;
for (size_t i=0; i<sizeof(rgFailure2Sensor)/sizeof(failure2Sensor_s); i++) {
const failure2Sensor_s* pFailure2Sensor = &rgFailure2Sensor[i];
if (highLatency2.failure_flags & pFailure2Sensor->failureBit) {
// Assume if reporting as unhealthy that is it present and enabled
newOnboardControlSensorsEnabled |= pFailure2Sensor->sensorBit;
}
}
if (newOnboardControlSensorsEnabled != _onboardControlSensorsEnabled) {
_onboardControlSensorsEnabled = newOnboardControlSensorsEnabled;
_onboardControlSensorsPresent = newOnboardControlSensorsEnabled;
_onboardControlSensorsUnhealthy = 0;
emit unhealthySensorsChanged();
}
}
void Vehicle::_handleAltitude(mavlink_message_t& message)
{
mavlink_altitude_t altitude;
mavlink_msg_altitude_decode(&message, &altitude);
// If data from GPS is available it takes precedence over ALTITUDE message
if (!_globalPositionIntMessageAvailable) {
_altitudeRelativeFact.setRawValue(altitude.altitude_relative);
if (!_gpsRawIntMessageAvailable) {
_altitudeAMSLFact.setRawValue(altitude.altitude_amsl);
}
}
}
void Vehicle::_setCapabilities(uint64_t capabilityBits)
{
_capabilityBits = capabilityBits;
_vehicleCapabilitiesKnown = true;
emit capabilitiesKnownChanged(true);
emit capabilityBitsChanged(_capabilityBits);
// This should potentially be turned into a user-facing warning
// if the general experience after deployment is that users want MAVLink 2
// but forget to upgrade their radio firmware
if (capabilityBits & MAV_PROTOCOL_CAPABILITY_MAVLINK2 && maxProtoVersion() < 200) {
qCDebug(VehicleLog) << QString("Vehicle does support MAVLink 2 but the link does not allow for it.");
}
QString supports("supports");
QString doesNotSupport("does not support");
qCDebug(VehicleLog) << QString("Vehicle %1 Mavlink 2.0").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ? supports : doesNotSupport);
qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_ITEM_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_INT ? supports : doesNotSupport);
qCDebug(VehicleLog) << QString("Vehicle %1 GeoFence").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE ? supports : doesNotSupport);
qCDebug(VehicleLog) << QString("Vehicle %1 RallyPoints").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY ? supports : doesNotSupport);
}
void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& message)
{
Q_UNUSED(link);
mavlink_autopilot_version_t autopilotVersion;
mavlink_msg_autopilot_version_decode(&message, &autopilotVersion);
_uid = (quint64)autopilotVersion.uid;
emit vehicleUIDChanged();
if (autopilotVersion.flight_sw_version != 0) {
int majorVersion, minorVersion, patchVersion;
FIRMWARE_VERSION_TYPE versionType;
majorVersion = (autopilotVersion.flight_sw_version >> (8*3)) & 0xFF;
minorVersion = (autopilotVersion.flight_sw_version >> (8*2)) & 0xFF;
patchVersion = (autopilotVersion.flight_sw_version >> (8*1)) & 0xFF;
versionType = (FIRMWARE_VERSION_TYPE)((autopilotVersion.flight_sw_version >> (8*0)) & 0xFF);
setFirmwareVersion(majorVersion, minorVersion, patchVersion, versionType);
}
if (px4Firmware()) {
// Lower 3 bytes is custom version
int majorVersion, minorVersion, patchVersion;
majorVersion = autopilotVersion.flight_custom_version[2];
minorVersion = autopilotVersion.flight_custom_version[1];
patchVersion = autopilotVersion.flight_custom_version[0];
setFirmwareCustomVersion(majorVersion, minorVersion, patchVersion);
// PX4 Firmware stores the first 16 characters of the git hash as binary, with the individual bytes in reverse order
_gitHash = "";
QByteArray array((char*)autopilotVersion.flight_custom_version, 8);
for (int i = 7; i >= 0; i--) {
_gitHash.append(QString("%1").arg(autopilotVersion.flight_custom_version[i], 2, 16, QChar('0')));
}
} else {
// APM Firmware stores the first 8 characters of the git hash as an ASCII character string
_gitHash = QString::fromUtf8((char*)autopilotVersion.flight_custom_version, 8);
}
emit gitHashChanged(_gitHash);
_setCapabilities(autopilotVersion.capabilities);
_startPlanRequest();
}
void Vehicle::_handleProtocolVersion(LinkInterface *link, mavlink_message_t& message)
{
Q_UNUSED(link);
mavlink_protocol_version_t protoVersion;
mavlink_msg_protocol_version_decode(&message, &protoVersion);
_setMaxProtoVersion(protoVersion.max_version);
}
void Vehicle::_setMaxProtoVersion(unsigned version) {
// Set only once or if we need to reduce the max version
if (_maxProtoVersion == 0 || version < _maxProtoVersion) {
qCDebug(VehicleLog) << "_setMaxProtoVersion before:after" << _maxProtoVersion << version;
_maxProtoVersion = version;