-
Notifications
You must be signed in to change notification settings - Fork 3.8k
/
Copy pathParameterManager.cc
1753 lines (1472 loc) · 69.3 KB
/
ParameterManager.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-2020 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 "ParameterManager.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
#include "QGCApplication.h"
#include "UASMessageHandler.h"
#include "FirmwarePlugin.h"
#include "UAS.h"
#include "JsonHelper.h"
#include <QEasingCurve>
#include <QFile>
#include <QDebug>
#include <QVariantAnimation>
#include <QJsonArray>
QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "ParameterManagerVerbose1Log")
QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "ParameterManagerVerbose2Log")
QGC_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog, "ParameterManagerDebugCacheFailureLog") // Turn on to debug parameter cache crc misses
const QHash<int, QString> _mavlinkCompIdHash {
{ MAV_COMP_ID_CAMERA, "Camera1" },
{ MAV_COMP_ID_CAMERA2, "Camera2" },
{ MAV_COMP_ID_CAMERA3, "Camera3" },
{ MAV_COMP_ID_CAMERA4, "Camera4" },
{ MAV_COMP_ID_CAMERA5, "Camera5" },
{ MAV_COMP_ID_CAMERA6, "Camera6" },
{ MAV_COMP_ID_SERVO1, "Servo1" },
{ MAV_COMP_ID_SERVO2, "Servo2" },
{ MAV_COMP_ID_SERVO3, "Servo3" },
{ MAV_COMP_ID_SERVO4, "Servo4" },
{ MAV_COMP_ID_SERVO5, "Servo5" },
{ MAV_COMP_ID_SERVO6, "Servo6" },
{ MAV_COMP_ID_SERVO7, "Servo7" },
{ MAV_COMP_ID_SERVO8, "Servo8" },
{ MAV_COMP_ID_SERVO9, "Servo9" },
{ MAV_COMP_ID_SERVO10, "Servo10" },
{ MAV_COMP_ID_SERVO11, "Servo11" },
{ MAV_COMP_ID_SERVO12, "Servo12" },
{ MAV_COMP_ID_SERVO13, "Servo13" },
{ MAV_COMP_ID_SERVO14, "Servo14" },
{ MAV_COMP_ID_GIMBAL, "Gimbal1" },
{ MAV_COMP_ID_ADSB, "ADSB" },
{ MAV_COMP_ID_OSD, "OSD" },
{ MAV_COMP_ID_FLARM, "FLARM" },
{ MAV_COMP_ID_GIMBAL2, "Gimbal2" },
{ MAV_COMP_ID_GIMBAL3, "Gimbal3" },
{ MAV_COMP_ID_GIMBAL4, "Gimbal4" },
{ MAV_COMP_ID_GIMBAL5, "Gimbal5" },
{ MAV_COMP_ID_GIMBAL6, "Gimbal6" },
{ MAV_COMP_ID_IMU, "IMU1" },
{ MAV_COMP_ID_IMU_2, "IMU2" },
{ MAV_COMP_ID_IMU_3, "IMU3" },
{ MAV_COMP_ID_GPS, "GPS1" },
{ MAV_COMP_ID_GPS2, "GPS2" }
};
const char* ParameterManager::_cachedMetaDataFilePrefix = "ParameterFactMetaData";
const char* ParameterManager::_jsonParametersKey = "parameters";
const char* ParameterManager::_jsonCompIdKey = "compId";
const char* ParameterManager::_jsonParamNameKey = "name";
const char* ParameterManager::_jsonParamValueKey = "value";
ParameterManager::ParameterManager(Vehicle* vehicle)
: QObject (vehicle)
, _vehicle (vehicle)
, _mavlink (nullptr)
, _loadProgress (0.0)
, _parametersReady (false)
, _missingParameters (false)
, _initialLoadComplete (false)
, _waitingForDefaultComponent (false)
, _saveRequired (false)
, _metaDataAddedToFacts (false)
, _logReplay (vehicle->priorityLink() && vehicle->priorityLink()->isLogReplay())
, _parameterSetMajorVersion (-1)
, _parameterMetaData (nullptr)
, _prevWaitingReadParamIndexCount (0)
, _prevWaitingReadParamNameCount (0)
, _prevWaitingWriteParamNameCount (0)
, _initialRequestRetryCount (0)
, _disableAllRetries (false)
, _indexBatchQueueActive (false)
, _totalParamCount (0)
{
_versionParam = vehicle->firmwarePlugin()->getVersionParam();
if (_vehicle->isOfflineEditingVehicle()) {
_loadOfflineEditingParams();
return;
}
_mavlink = qgcApp()->toolbox()->mavlinkProtocol();
_initialRequestTimeoutTimer.setSingleShot(true);
_initialRequestTimeoutTimer.setInterval(5000);
connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_initialRequestTimeout);
_waitingParamTimeoutTimer.setSingleShot(true);
_waitingParamTimeoutTimer.setInterval(3000);
connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_waitingParamTimeout);
connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterManager::_parameterUpdate);
// Ensure the cache directory exists
QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
if (_vehicle->highLatencyLink()) {
// High latency links don't load parameters
_parametersReady = true;
_missingParameters = true;
_initialLoadComplete = true;
_waitingForDefaultComponent = false;
emit parametersReadyChanged(_parametersReady);
emit missingParametersChanged(_missingParameters);
} else if (!_logReplay){
refreshAllParameters();
}
}
ParameterManager::~ParameterManager()
{
delete _parameterMetaData;
}
void ParameterManager::_updateProgressBar(void)
{
int waitingReadParamIndexCount = 0;
int waitingReadParamNameCount = 0;
int waitingWriteParamCount = 0;
for (int compId: _waitingReadParamIndexMap.keys()) {
waitingReadParamIndexCount += _waitingReadParamIndexMap[compId].count();
}
for(int compId: _waitingReadParamNameMap.keys()) {
waitingReadParamNameCount += _waitingReadParamNameMap[compId].count();
}
for(int compId: _waitingWriteParamNameMap.keys()) {
waitingWriteParamCount += _waitingWriteParamNameMap[compId].count();
}
if (waitingReadParamIndexCount == 0) {
if (_readParamIndexProgressActive) {
_readParamIndexProgressActive = false;
_setLoadProgress(0.0);
return;
}
} else {
_readParamIndexProgressActive = true;
_setLoadProgress((double)(_totalParamCount - waitingReadParamIndexCount) / (double)_totalParamCount);
return;
}
if (waitingWriteParamCount == 0) {
if (_writeParamProgressActive) {
_writeParamProgressActive = false;
_waitingWriteParamBatchCount = 0;
_setLoadProgress(0.0);
emit pendingWritesChanged(false);
return;
}
} else {
_writeParamProgressActive = true;
_setLoadProgress((double)(qMax(_waitingWriteParamBatchCount - waitingWriteParamCount, 1)) / (double)(_waitingWriteParamBatchCount + 1));
emit pendingWritesChanged(true);
return;
}
if (waitingReadParamNameCount == 0) {
if (_readParamNameProgressActive) {
_readParamNameProgressActive = false;
_waitingReadParamNameBatchCount = 0;
_setLoadProgress(0.0);
return;
}
} else {
_readParamNameProgressActive = true;
_setLoadProgress((double)(qMax(_waitingReadParamNameBatchCount - waitingReadParamNameCount, 1)) / (double)(_waitingReadParamNameBatchCount + 1));
return;
}
}
/// Called whenever a parameter is updated or first seen.
void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value)
{
// Is this for our uas?
if (vehicleId != _vehicle->id()) {
return;
}
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
"_parameterUpdate" <<
"name:" << parameterName <<
"count:" << parameterCount <<
"index:" << parameterId <<
"mavType:" << mavType <<
"value:" << value <<
")";
// ArduPilot has this strange behavior of streaming parameters that we didn't ask for. This even happens before it responds to the
// PARAM_REQUEST_LIST. We disregard any of this until the initial request is responded to.
if (parameterId == 65535 && parameterName != "_HASH_CHECK" && _initialRequestTimeoutTimer.isActive()) {
qCDebug(ParameterManagerVerbose1Log) << "Disregarding unrequested param prior to initial list response" << parameterName;
return;
}
_initialRequestTimeoutTimer.stop();
#if 0
if (!_initialLoadComplete && !_indexBatchQueueActive) {
// Handy for testing retry logic
static int counter = 0;
if (counter++ & 0x8) {
qCDebug(ParameterManagerLog) << "Artificial discard" << counter;
return;
}
}
#endif
#if 0
// Use this to test missing default component id
if (componentId == 50) {
return;
}
#endif
if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") {
if (!_initialLoadComplete && !_logReplay) {
/* we received a cache hash, potentially load from cache */
_tryCacheHashLoad(vehicleId, componentId, value);
}
return;
}
// Used to debug cache crc misses (turn on ParameterManagerDebugCacheFailureLog)
if (!_initialLoadComplete && !_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
if (_debugCacheMap[componentId].contains(parameterName)) {
const ParamTypeVal& cacheParamTypeVal = _debugCacheMap[componentId][parameterName];
size_t dataSize = FactMetaData::typeToSize(static_cast<FactMetaData::ValueType_t>(cacheParamTypeVal.first));
const void *cacheData = cacheParamTypeVal.second.constData();
const void *vehicleData = value.constData();
if (memcmp(cacheData, vehicleData, dataSize)) {
qDebug() << "Cache/Vehicle values differ for name:cache:actual" << parameterName << value << cacheParamTypeVal.second;
}
_debugCacheParamSeen[componentId][parameterName] = true;
} else {
qDebug() << "Parameter missing from cache" << parameterName;
}
}
_initialRequestTimeoutTimer.stop();
_waitingParamTimeoutTimer.stop();
_dataMutex.lock();
// Update our total parameter counts
if (!_paramCountMap.contains(componentId)) {
_paramCountMap[componentId] = parameterCount;
_totalParamCount += parameterCount;
}
// If we've never seen this component id before, setup the wait lists.
if (!_waitingReadParamIndexMap.contains(componentId)) {
// Add all indices to the wait list, parameter index is 0-based
for (int waitingIndex=0; waitingIndex<parameterCount; waitingIndex++) {
// This will add the new component id, as well as the the new waiting index and set the retry count for that index to 0
_waitingReadParamIndexMap[componentId][waitingIndex] = 0;
}
// The read and write waiting lists for this component are initialized the empty
_waitingReadParamNameMap[componentId] = QMap<QString, int>();
_waitingWriteParamNameMap[componentId] = QMap<QString, int>();
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Seeing component for first time - paramcount:" << parameterCount;
}
bool componentParamsComplete = false;
if (_waitingReadParamIndexMap[componentId].count() == 1) {
// We need to know when we get the last param from a component in order to complete setup
componentParamsComplete = true;
}
if (!_waitingReadParamIndexMap[componentId].contains(parameterId) &&
!_waitingReadParamNameMap[componentId].contains(parameterName) &&
!_waitingWriteParamNameMap[componentId].contains(parameterName)) {
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Unrequested param update" << parameterName;
}
// Remove this parameter from the waiting lists
if (_waitingReadParamIndexMap[componentId].contains(parameterId)) {
_waitingReadParamIndexMap[componentId].remove(parameterId);
_indexBatchQueue.removeOne(parameterId);
_fillIndexBatchQueue(false /* waitingParamTimeout */);
}
_waitingReadParamNameMap[componentId].remove(parameterName);
_waitingWriteParamNameMap[componentId].remove(parameterName);
if (_waitingReadParamIndexMap[componentId].count()) {
qCDebug(ParameterManagerVerbose2Log) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
}
if (_waitingReadParamNameMap[componentId].count()) {
qCDebug(ParameterManagerVerbose2Log) << _logVehiclePrefix(componentId) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
}
if (_waitingWriteParamNameMap[componentId].count()) {
qCDebug(ParameterManagerVerbose2Log) << _logVehiclePrefix(componentId) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];
}
// Track how many parameters we are still waiting for
int waitingReadParamIndexCount = 0;
int waitingReadParamNameCount = 0;
int waitingWriteParamNameCount = 0;
for(int waitingComponentId: _waitingReadParamIndexMap.keys()) {
waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
}
if (waitingReadParamIndexCount) {
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
}
for(int waitingComponentId: _waitingReadParamNameMap.keys()) {
waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
}
if (waitingReadParamNameCount) {
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
}
for(int waitingComponentId: _waitingWriteParamNameMap.keys()) {
waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
}
if (waitingWriteParamNameCount) {
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
}
int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
if (totalWaitingParamCount) {
// More params to wait for, restart timer
_waitingParamTimeoutTimer.start();
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
} else {
if (!_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
// Still waiting for parameters from default component
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer (still waiting for default component params)";
_waitingParamTimeoutTimer.start();
} else {
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
}
}
\
_updateProgressBar();
// Get parameter set version
if (!_versionParam.isEmpty() && _versionParam == parameterName) {
_parameterSetMajorVersion = value.toInt();
}
if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) {
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Adding new fact" << parameterName;
FactMetaData::ValueType_t factType;
switch (mavType) {
case MAV_PARAM_TYPE_UINT8:
factType = FactMetaData::valueTypeUint8;
break;
case MAV_PARAM_TYPE_INT8:
factType = FactMetaData::valueTypeInt8;
break;
case MAV_PARAM_TYPE_UINT16:
factType = FactMetaData::valueTypeUint16;
break;
case MAV_PARAM_TYPE_INT16:
factType = FactMetaData::valueTypeInt16;
break;
case MAV_PARAM_TYPE_UINT32:
factType = FactMetaData::valueTypeUint32;
break;
case MAV_PARAM_TYPE_INT32:
factType = FactMetaData::valueTypeInt32;
break;
case MAV_PARAM_TYPE_UINT64:
factType = FactMetaData::valueTypeUint64;
break;
case MAV_PARAM_TYPE_INT64:
factType = FactMetaData::valueTypeInt64;
break;
case MAV_PARAM_TYPE_REAL32:
factType = FactMetaData::valueTypeFloat;
break;
case MAV_PARAM_TYPE_REAL64:
factType = FactMetaData::valueTypeDouble;
break;
default:
factType = FactMetaData::valueTypeInt32;
qCritical() << "Unsupported fact type" << mavType;
break;
}
Fact* fact = new Fact(componentId, parameterName, factType, this);
_mapParameterName2Variant[componentId][parameterName] = QVariant::fromValue(fact);
// We need to know when the fact changes from QML so that we can send the new value to the parameter manager
connect(fact, &Fact::_containerRawValueChanged, this, &ParameterManager::_valueUpdated);
}
_dataMutex.unlock();
Fact* fact = nullptr;
if (_mapParameterName2Variant[componentId].contains(parameterName)) {
fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
}
if (fact) {
fact->_containerSetRawValue(value);
} else {
qWarning() << "Internal error";
}
if (componentParamsComplete) {
if (componentId == _vehicle->defaultComponentId()) {
// Add meta data to default component. We need to do this before we setup the group map since group
// map requires meta data.
_addMetaDataToDefaultComponent();
}
// When we are getting the very last component param index, reset the group maps to update for the
// new params. By handling this here, we can pick up components which finish up later than the default
// component param set.
_setupComponentCategoryMap(componentId);
}
// Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
// which invalidate the cache. The Solo also streams param updates in flight for things like gimbal values
// which in turn causes a perf problem with all the param cache updates.
if (!_logReplay && _vehicle->px4Firmware()) {
if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0 && readWaitingParamCount == 0) {
// All reads just finished, update the cache
_writeLocalParamCache(vehicleId, componentId);
}
}
_prevWaitingReadParamIndexCount = waitingReadParamIndexCount;
_prevWaitingReadParamNameCount = waitingReadParamNameCount;
_prevWaitingWriteParamNameCount = waitingWriteParamNameCount;
_checkInitialLoadComplete();
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
}
/// Connected to Fact::valueUpdated
///
/// Writes the parameter to mavlink, sets up for write wait
void ParameterManager::_valueUpdated(const QVariant& value)
{
Fact* fact = qobject_cast<Fact*>(sender());
if (!fact) {
qWarning() << "Internal error";
return;
}
int componentId = fact->componentId();
QString name = fact->name();
_dataMutex.lock();
if (_waitingWriteParamNameMap.contains(componentId)) {
if (_waitingWriteParamNameMap[componentId].contains(name)) {
_waitingWriteParamNameMap[componentId].remove(name);
} else {
_waitingWriteParamBatchCount++;
}
_waitingWriteParamNameMap[componentId][name] = 0; // Add new entry and set retry count
_updateProgressBar();
_waitingParamTimeoutTimer.start();
_saveRequired = true;
} else {
qWarning() << "Internal error";
}
_dataMutex.unlock();
_writeParameterRaw(componentId, fact->name(), value);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Set parameter - name:" << name << value << "(_waitingParamTimeoutTimer started)";
}
void ParameterManager::refreshAllParameters(uint8_t componentId)
{
if (_logReplay) {
return;
}
_dataMutex.lock();
if (!_initialLoadComplete) {
_initialRequestTimeoutTimer.start();
}
// Reset index wait lists
for (int cid: _paramCountMap.keys()) {
// Add/Update all indices to the wait list, parameter index is 0-based
if(componentId != MAV_COMP_ID_ALL && componentId != cid)
continue;
for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
// This will add a new waiting index if needed and set the retry count for that index to 0
_waitingReadParamIndexMap[cid][waitingIndex] = 0;
}
}
_dataMutex.unlock();
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_message_t msg;
mavlink_msg_param_request_list_pack_chan(mavlink->getSystemId(),
mavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
_vehicle->id(),
componentId);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
QString what = (componentId == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentId);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Request to refresh all parameters for component ID:" << what;
}
/// Translates FactSystem::defaultComponentId to real component id if needed
int ParameterManager::_actualComponentId(int componentId)
{
if (componentId == FactSystem::defaultComponentId) {
componentId = _vehicle->defaultComponentId();
if (componentId == FactSystem::defaultComponentId) {
qWarning() << _logVehiclePrefix(-1) << "Default component id not set";
}
}
return componentId;
}
void ParameterManager::refreshParameter(int componentId, const QString& paramName)
{
componentId = _actualComponentId(componentId);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << paramName << ")";
_dataMutex.lock();
if (_waitingReadParamNameMap.contains(componentId)) {
QString mappedParamName = _remapParamNameToVersion(paramName);
if (_waitingReadParamNameMap[componentId].contains(mappedParamName)) {
_waitingReadParamNameMap[componentId].remove(mappedParamName);
} else {
_waitingReadParamNameBatchCount++;
}
_waitingReadParamNameMap[componentId][mappedParamName] = 0; // Add new wait entry and update retry count
_updateProgressBar();
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "restarting _waitingParamTimeout";
_waitingParamTimeoutTimer.start();
} else {
qWarning() << "Internal error";
}
_dataMutex.unlock();
_readParameterRaw(componentId, paramName, -1);
}
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
{
componentId = _actualComponentId(componentId);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
for(const QString ¶mName: _mapParameterName2Variant[componentId].keys()) {
if (paramName.startsWith(namePrefix)) {
refreshParameter(componentId, paramName);
}
}
}
bool ParameterManager::parameterExists(int componentId, const QString& paramName)
{
bool ret = false;
componentId = _actualComponentId(componentId);
if (_mapParameterName2Variant.contains(componentId)) {
ret = _mapParameterName2Variant[componentId].contains(_remapParamNameToVersion(paramName));
}
return ret;
}
Fact* ParameterManager::getParameter(int componentId, const QString& paramName)
{
componentId = _actualComponentId(componentId);
QString mappedParamName = _remapParamNameToVersion(paramName);
if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(mappedParamName)) {
qgcApp()->reportMissingParameter(componentId, mappedParamName);
return &_defaultFact;
}
return _mapParameterName2Variant[componentId][mappedParamName].value<Fact*>();
}
QStringList ParameterManager::parameterNames(int componentId)
{
QStringList names;
for(const QString ¶mName: _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
names << paramName;
}
return names;
}
void ParameterManager::_setupComponentCategoryMap(int componentId)
{
if (componentId == _vehicle->defaultComponentId()) {
_setupDefaultComponentCategoryMap();
return;
}
ComponentCategoryMapType& componentCategoryMap = _componentCategoryMaps[componentId];
QString category = getComponentCategory(componentId);
// Must be able to handle being called multiple times
componentCategoryMap.clear();
// Fill parameters into the group determined by param name
for (const QString ¶mName: _mapParameterName2Variant[componentId].keys()) {
int i = paramName.indexOf("_");
if (i > 0) {
componentCategoryMap[category][paramName.left(i)] += paramName;
} else {
componentCategoryMap[category][tr("Misc")] += paramName;
}
}
// Memorize category for component ID
if (!_componentCategoryHash.contains(category)) {
_componentCategoryHash.insert(category, componentId);
}
}
void ParameterManager::_setupDefaultComponentCategoryMap(void)
{
ComponentCategoryMapType& defaultComponentCategoryMap = _componentCategoryMaps[_vehicle->defaultComponentId()];
// Must be able to handle being called multiple times
defaultComponentCategoryMap.clear();
for (const QString ¶mName: _mapParameterName2Variant[_vehicle->defaultComponentId()].keys()) {
Fact* fact = _mapParameterName2Variant[_vehicle->defaultComponentId()][paramName].value<Fact*>();
defaultComponentCategoryMap[fact->category()][fact->group()] += paramName;
}
}
QString ParameterManager::getComponentCategory(int componentId)
{
if (_mavlinkCompIdHash.contains(componentId)) {
return tr("Component %1 (%2)").arg(_mavlinkCompIdHash.value(componentId)).arg(componentId);
}
QString componentCategoryPrefix = tr("Component ");
return QString("%1%2").arg(componentCategoryPrefix).arg(componentId);
}
const QMap<QString, QMap<QString, QStringList> >& ParameterManager::getComponentCategoryMap(int componentId)
{
return _componentCategoryMaps[componentId];
}
int ParameterManager::getComponentId(const QString& category)
{
return (_componentCategoryHash.contains(category)) ? _componentCategoryHash.value(category) : _vehicle->defaultComponentId();
}
/// Requests missing index based parameters from the vehicle.
/// @param waitingParamTimeout: true: being called due to timeout, false: being called to re-fill the batch queue
/// return true: Parameters were requested, false: No more requests needed
bool ParameterManager::_fillIndexBatchQueue(bool waitingParamTimeout)
{
if (!_indexBatchQueueActive) {
return false;
}
const int maxBatchSize = 10;
if (waitingParamTimeout) {
// We timed out, clear the queue and try again
qCDebug(ParameterManagerLog) << "Refilling index based batch queue due to timeout";
_indexBatchQueue.clear();
} else {
qCDebug(ParameterManagerLog) << "Refilling index based batch queue due to received parameter";
}
for(int componentId: _waitingReadParamIndexMap.keys()) {
if (_waitingReadParamIndexMap[componentId].count()) {
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count();
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
}
for(int paramIndex: _waitingReadParamIndexMap[componentId].keys()) {
if (_indexBatchQueue.contains(paramIndex)) {
// Don't add more than once
continue;
}
if (_indexBatchQueue.count() > maxBatchSize) {
break;
}
_waitingReadParamIndexMap[componentId][paramIndex]++; // Bump retry count
if (_disableAllRetries || _waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
// Give up on this index
_failedReadParamIndexMap[componentId] << paramIndex;
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Giving up on (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
_waitingReadParamIndexMap[componentId].remove(paramIndex);
} else {
// Retry again
_indexBatchQueue.append(paramIndex);
_readParameterRaw(componentId, "", paramIndex);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
}
}
}
return _indexBatchQueue.count() != 0;
}
void ParameterManager::_waitingParamTimeout(void)
{
if (_logReplay) {
return;
}
bool paramsRequested = false;
const int maxBatchSize = 10;
int batchCount = 0;
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "_waitingParamTimeout";
// Now that we have timed out for possibly the first time we can activate the index batch queue
_indexBatchQueueActive = true;
// First check for any missing parameters from the initial index based load
paramsRequested = _fillIndexBatchQueue(true /* waitingParamTimeout */);
if (!paramsRequested && !_waitingForDefaultComponent && !_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
// Initial load is complete but we still don't have any default component params. Wait one more cycle to see if the
// any show up.
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId() << _mapParameterName2Variant.keys();
_waitingParamTimeoutTimer.start();
_waitingForDefaultComponent = true;
return;
}
_waitingForDefaultComponent = false;
_checkInitialLoadComplete();
if (!paramsRequested) {
for(int componentId: _waitingWriteParamNameMap.keys()) {
for(const QString ¶mName: _waitingWriteParamNameMap[componentId].keys()) {
paramsRequested = true;
_waitingWriteParamNameMap[componentId][paramName]++; // Bump retry count
if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
_writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue());
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
if (++batchCount > maxBatchSize) {
goto Out;
}
} else {
// Exceeded max retry count, notify user
_waitingWriteParamNameMap[componentId].remove(paramName);
QString errorMsg = tr("Parameter write failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showAppMessage(errorMsg);
}
}
}
}
if (!paramsRequested) {
for(int componentId: _waitingReadParamNameMap.keys()) {
for(const QString ¶mName: _waitingReadParamNameMap[componentId].keys()) {
paramsRequested = true;
_waitingReadParamNameMap[componentId][paramName]++; // Bump retry count
if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
_readParameterRaw(componentId, paramName, -1);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
if (++batchCount > maxBatchSize) {
goto Out;
}
} else {
// Exceeded max retry count, notify user
_waitingReadParamNameMap[componentId].remove(paramName);
QString errorMsg = tr("Parameter read failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showAppMessage(errorMsg);
}
}
}
}
Out:
if (paramsRequested) {
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - re-request";
_waitingParamTimeoutTimer.start();
}
}
void ParameterManager::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
{
mavlink_message_t msg;
char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];
strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
mavlink_msg_param_request_read_pack_chan(_mavlink->getSystemId(), // QGC system id
_mavlink->getComponentId(), // QGC component id
_vehicle->priorityLink()->mavlinkChannel(),
&msg, // Pack into this mavlink_message_t
_vehicle->id(), // Target system id
componentId, // Target component id
fixedParamName, // Named parameter being requested
paramIndex); // Parameter index being requested, -1 for named
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
}
void ParameterManager::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
{
mavlink_param_set_t p;
mavlink_param_union_t union_value;
memset(&p, 0, sizeof(p));
FactMetaData::ValueType_t factType = getParameter(componentId, paramName)->type();
p.param_type = _factTypeToMavType(factType);
switch (factType) {
case FactMetaData::valueTypeUint8:
union_value.param_uint8 = (uint8_t)value.toUInt();
break;
case FactMetaData::valueTypeInt8:
union_value.param_int8 = (int8_t)value.toInt();
break;
case FactMetaData::valueTypeUint16:
union_value.param_uint16 = (uint16_t)value.toUInt();
break;
case FactMetaData::valueTypeInt16:
union_value.param_int16 = (int16_t)value.toInt();
break;
case FactMetaData::valueTypeUint32:
union_value.param_uint32 = (uint32_t)value.toUInt();
break;
case FactMetaData::valueTypeFloat:
union_value.param_float = value.toFloat();
break;
default:
qCritical() << "Unsupported fact type" << factType;
// fall through
case FactMetaData::valueTypeInt32:
union_value.param_int32 = (int32_t)value.toInt();
break;
}
p.param_value = union_value.param_float;
p.target_system = (uint8_t)_vehicle->id();
p.target_component = (uint8_t)componentId;
strncpy(p.param_id, paramName.toStdString().c_str(), sizeof(p.param_id));
mavlink_message_t msg;
mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
&p);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
}
void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
{
CacheMapName2ParamTypeVal cacheMap;
for(const QString& paramName: _mapParameterName2Variant[componentId].keys()) {
const Fact *fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
cacheMap[paramName] = ParamTypeVal(fact->type(), fact->rawValue());
}
QFile cacheFile(parameterCacheFile(vehicleId, componentId));
cacheFile.open(QIODevice::WriteOnly | QIODevice::Truncate);
QDataStream ds(&cacheFile);
ds << cacheMap;
}
QDir ParameterManager::parameterCacheDir()
{
const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
return spath + QDir::separator() + "ParamCache";
}
QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
{
return parameterCacheDir().filePath(QString("%1_%2.v2").arg(vehicleId).arg(componentId));
}
void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value)
{
qCInfo(ParameterManagerLog) << "Attemping load from cache";
uint32_t crc32_value = 0;
/* The datastructure of the cache table */
CacheMapName2ParamTypeVal cacheMap;
QFile cacheFile(parameterCacheFile(vehicleId, componentId));
if (!cacheFile.exists()) {
/* no local cache, just wait for them to come in*/
return;
}
cacheFile.open(QIODevice::ReadOnly);
/* Deserialize the parameter cache table */
QDataStream ds(&cacheFile);
ds >> cacheMap;
// Load parameter meta data for the version number stored in cache.
// We need meta data so we have access to the volatile bit
if (cacheMap.contains(_versionParam)) {
_parameterSetMajorVersion = cacheMap[_versionParam].second.toInt();
}
_loadMetaData();
/* compute the crc of the local cache to check against the remote */
FirmwarePlugin* firmwarePlugin = _vehicle->firmwarePlugin();
for (const QString& name: cacheMap.keys()) {
bool volatileValue = false;
FactMetaData* metaData = firmwarePlugin->getMetaDataForFact(_parameterMetaData, name, _vehicle->vehicleType());
if (metaData) {
volatileValue = metaData->volatileValue();
}
if (volatileValue) {
// Does not take part in CRC
qCDebug(ParameterManagerLog) << "Volatile parameter" << name;
} else {
const ParamTypeVal& paramTypeVal = cacheMap[name];
const void *vdat = paramTypeVal.second.constData();
const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
crc32_value = QGC::crc32((const uint8_t *)qPrintable(name), name.length(), crc32_value);
crc32_value = QGC::crc32((const uint8_t *)vdat, FactMetaData::typeToSize(fact_type), crc32_value);
}
}
/* if the two param set hashes match, just load from the disk */
if (crc32_value == hash_value.toUInt()) {
qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());
int count = cacheMap.count();
int index = 0;
for (const QString& name: cacheMap.keys()) {
const ParamTypeVal& paramTypeVal = cacheMap[name];
const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
const int mavType = _factTypeToMavType(fact_type);
_parameterUpdate(vehicleId, componentId, name, count, index++, mavType, paramTypeVal.second);
}
// Return the hash value to notify we don't want any more updates
mavlink_param_set_t p;
mavlink_param_union_t union_value;
memset(&p, 0, sizeof(p));
p.param_type = MAV_PARAM_TYPE_UINT32;
strncpy(p.param_id, "_HASH_CHECK", sizeof(p.param_id));
union_value.param_uint32 = crc32_value;
p.param_value = union_value.param_float;
p.target_system = (uint8_t)_vehicle->id();
p.target_component = (uint8_t)componentId;
mavlink_message_t msg;
mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
&p);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);