QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ParameterEditorController.cc
Go to the documentation of this file.
3#include "AppMessages.h"
4#include "ParameterManager.h"
5#include "AppSettings.h"
6#include "SettingsManager.h"
7#include "Vehicle.h"
9
10QGC_LOGGING_CATEGORY(ParameterEditorControllerLog, "QMLControls.ParameterEditorController")
11
13 : QAbstractTableModel(parent)
14{
15
16}
17
22
23int ParameterTableModel::rowCount(const QModelIndex& /*parent*/) const
24{
25 return _tableData.count();
26}
27
28int ParameterTableModel::columnCount(const QModelIndex & /*parent*/) const
29{
30 return _tableViewColCount;
31}
32
33QVariant ParameterTableModel::data(const QModelIndex &index, int role) const
34{
35 if (!index.isValid()) {
36 return QVariant();
37 }
38
39 if (index.row() < 0 || index.row() >= _tableData.count()) {
40 return QVariant();
41 }
42 if (index.column() < 0 || index.column() >= _tableViewColCount) {
43 return QVariant();
44 }
45
46 switch (role) {
47 case Qt::DisplayRole:
48 return QVariant::fromValue(_tableData[index.row()][index.column()]);
49 case FactRole:
50 return QVariant::fromValue(_tableData[index.row()][ValueColumn]);
51 default:
52 return QVariant();
53 }
54}
55
56QVariant ParameterTableModel::headerData(int section, Qt::Orientation orientation, int role) const
57{
58 if (orientation != Qt::Horizontal || role != Qt::DisplayRole) {
59 return QVariant();
60 }
61
62 switch (section) {
63 case FavColumn: return tr("Fav");
64 case NameColumn: return tr("Name");
65 case ValueColumn: return tr("Value");
66 case DescriptionColumn: return tr("Description");
67 default: return QVariant();
68 }
69}
70
71QHash<int, QByteArray> ParameterTableModel::roleNames() const
72{
73 return {
74 {Qt::DisplayRole, "display"},
75 {FactRole, "fact"}
76 };
77}
78
80{
81 beginReset();
82 _tableData.clear();
83 endReset();
84}
85
87{
88 insert(rowCount(), fact);
89}
90
92{
93 if (row < 0 || row > rowCount()) {
94 qWarning() << "Invalid row row:rowCount" << row << rowCount() << Q_FUNC_INFO;
95 row = qMax(qMin(row, rowCount()), 0);
96 }
97
98 ColumnData colData(_tableViewColCount, QString());
99 colData[FavColumn] = QString();
100 colData[NameColumn] = fact->name();
101 colData[ValueColumn] = QVariant::fromValue(fact);
102 colData[DescriptionColumn] = fact->shortDescription();
103
104 if (!_isResetting()) {
105 beginInsertRows(QModelIndex(), row, row);
106 }
107 _tableData.insert(row, colData);
108 if (!_isResetting()) {
109 endInsertRows();
111 }
112}
113
115{
116 _resetNestingCount++;
117
118 if (_resetNestingCount == 1) {
119 beginResetModel();
120 }
121}
122
124{
125 if (_resetNestingCount == 0) {
126 qWarning() << "ParameterTableModel::endReset called without prior beginReset";
127 return;
128 }
129 _resetNestingCount--;
130 if (_resetNestingCount == 0) {
131 endResetModel();
133 }
134}
135
137{
138 if (row < 0 || row >= _tableData.count()) {
139 qWarning() << "Invalid row row:rowCount" << row << _tableData.count() << Q_FUNC_INFO;
140 return nullptr;
141 }
142
143 return _tableData[row][ValueColumn].value<Fact*>();
144}
145
146
148 : QObject(parent)
149{
150
151}
152
154 : FactPanelController(parent)
155 , _parameterMgr(_vehicle->parameterManager())
156{
157 // qCDebug(ParameterEditorControllerLog) << Q_FUNC_INFO << this;
158
159 _buildLists();
160
161 _searchTimer.setSingleShot(true);
162 _searchTimer.setInterval(300);
163
164 connect(this, &ParameterEditorController::currentCategoryChanged, this, &ParameterEditorController::_currentCategoryChanged);
165 connect(this, &ParameterEditorController::currentGroupChanged, this, &ParameterEditorController::_currentGroupChanged);
166 connect(this, &ParameterEditorController::searchTextChanged, this, &ParameterEditorController::_searchTextChanged);
167 connect(this, &ParameterEditorController::showModifiedOnlyChanged, this, &ParameterEditorController::_searchTextChanged);
168 connect(this, &ParameterEditorController::showFavoritesOnlyChanged, this, &ParameterEditorController::_searchTextChanged);
169 connect(this, &ParameterEditorController::hideReadOnlyChanged, this, &ParameterEditorController::_hideReadOnlyChanged);
170 connect(&_searchTimer, &QTimer::timeout, this, &ParameterEditorController::_performSearch);
171 connect(_parameterMgr, &ParameterManager::factAdded, this, &ParameterEditorController::_factAdded);
172
173 _loadFavorites();
174
175 ParameterEditorCategory* category = _categories.count() ? _categories.value<ParameterEditorCategory*>(0) : nullptr;
176 setCurrentCategory(category);
177}
178
180{
181 // qCDebug(ParameterEditorControllerLog) << Q_FUNC_INFO << this;
182}
183
184void ParameterEditorController::_buildListsForComponent(int compId)
185{
186 for (const QString& factName: _parameterMgr->parameterNames(compId)) {
187 Fact* fact = _parameterMgr->getParameter(compId, factName);
188
189 if (_hideReadOnly && fact->readOnly()) {
190 continue;
191 }
192
193 ParameterEditorCategory* category = nullptr;
194 if (_mapCategoryName2Category.contains(fact->category())) {
195 category = _mapCategoryName2Category[fact->category()];
196 } else {
197 category = new ParameterEditorCategory(this);
198 category->name = fact->category();
199 _mapCategoryName2Category[fact->category()] = category;
200 _categories.append(category);
201 }
202
203 ParameterEditorGroup* group = nullptr;
204 if (category->mapGroupName2Group.contains(fact->group())) {
205 group = category->mapGroupName2Group[fact->group()];
206 } else {
207 group = new ParameterEditorGroup(this);
208 group->componentId = compId;
209 group->name = fact->group();
210 category->mapGroupName2Group[fact->group()] = group;
211 category->groups.append(group);
212 }
213
214 group->facts.append(fact);
215 }
216}
217
218void ParameterEditorController::_buildLists(void)
219{
220 _currentCategory = nullptr;
221 _currentGroup = nullptr;
222 _parameters = nullptr;
223 _mapCategoryName2Category.clear();
224 _categories.clearAndDeleteContents();
225 emit parametersChanged();
226
227 // Autopilot component should always be first list
228 _buildListsForComponent(MAV_COMP_ID_AUTOPILOT1);
229
230 // "Standard" category should always be first
231 for (int i=0; i<_categories.count(); i++) {
232 ParameterEditorCategory* category = _categories.value<ParameterEditorCategory*>(i);
233 if (category->name == "Standard" && i != 0) {
234 _categories.removeAt(i);
235 _categories.insert(0, category);
236 break;
237 }
238 }
239
240 // Default category should always be last
241 for (int i=0; i<_categories.count(); i++) {
242 ParameterEditorCategory* category = _categories.value<ParameterEditorCategory*>(i);
243 if (category->name == FactMetaData::kDefaultCategory) {
244 if (i != _categories.count() - 1) {
245 _categories.removeAt(i);
246 _categories.append(category);
247 }
248 break;
249 }
250 }
251
252 // Now add other random components
253 for (int compId: _parameterMgr->componentIds()) {
254 if (compId != MAV_COMP_ID_AUTOPILOT1) {
255 _buildListsForComponent(compId);
256 }
257 }
258
259 // Default group should always be last
260 for (int i=0; i<_categories.count(); i++) {
261 ParameterEditorCategory* category = _categories.value<ParameterEditorCategory*>(i);
262 for (int j=0; j<category->groups.count(); j++) {
264 if (group->name == FactMetaData::kDefaultGroup) {
265 if (j != _categories.count() - 1) {
266 category->groups.removeAt(j);
267 category->groups.append(group);
268 }
269 break;
270 }
271 }
272 }
273}
274
275void ParameterEditorController::_factAdded(int compId, Fact* fact)
276{
277 if (_hideReadOnly && fact->readOnly()) {
278 return;
279 }
280
281 bool inserted = false;
282 ParameterEditorCategory* category = nullptr;
283
284 if (_mapCategoryName2Category.contains(fact->category())) {
285 category = _mapCategoryName2Category[fact->category()];
286 } else {
287 category = new ParameterEditorCategory(this);
288 category->name = fact->category();
289 _mapCategoryName2Category[fact->category()] = category;
290
291 // Insert in sorted order
292 inserted = false;
293 for (int i=0; i<_categories.count(); i++) {
294 if (_categories.value<ParameterEditorCategory*>(i)->name > category->name) {
295 _categories.insert(i, category);
296 inserted = true;
297 break;
298 }
299 }
300 if (!inserted) {
301 _categories.append(category);
302 }
303 }
304
305 ParameterEditorGroup* group = nullptr;
306 if (category->mapGroupName2Group.contains(fact->group())) {
307 group = category->mapGroupName2Group[fact->group()];
308 } else {
309 group = new ParameterEditorGroup(this);
310 group->componentId = compId;
311 group->name = fact->group();
312 category->mapGroupName2Group[fact->group()] = group;
313
314 // Insert in sorted order
315 QmlObjectListModel& groups = category->groups;
316 inserted = false;
317 for (int i=0; i<groups.count(); i++) {
318 if (groups.value<ParameterEditorGroup*>(i)->name > group->name) {
319 groups.insert(i, group);
320 inserted = true;
321 break;
322 }
323 }
324 if (!inserted) {
325 groups.append(group);
326 }
327 }
328
329 // Insert in sorted order
330 auto& facts = group->facts;
331 for (int i=0; i<facts.rowCount(); i++) {
332 if (facts.factAt(i)->name() > fact->name()) {
333 facts.insert(i, fact);
334 return;
335 }
336 }
337 facts.append(fact);
338}
339
340void ParameterEditorController::saveToFile(const QString& filename)
341{
342 if (!filename.isEmpty()) {
343 QString parameterFilename = filename;
344 if (!QFileInfo(filename).fileName().contains(".")) {
345 parameterFilename += QString(".%1").arg(AppSettings::parameterFileExtension);
346 }
347
348 QFile file(parameterFilename);
349
350 if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
351 QGC::showAppMessage(tr("Unable to create file: %1").arg(parameterFilename));
352 return;
353 }
354
355 QTextStream stream(&file);
356 _parameterMgr->writeParametersToStream(stream);
357 file.close();
358 }
359}
360
362{
363 _diffList.clearAndDeleteContents();
364 _diffOtherVehicle = false;
365 _diffMultipleComponents = false;
366
367 emit diffOtherVehicleChanged(_diffOtherVehicle);
368 emit diffMultipleComponentsChanged(_diffMultipleComponents);
369}
370
372{
373 for (int i=0; i<_diffList.count(); i++) {
374 ParameterEditorDiff* paramDiff = _diffList.value<ParameterEditorDiff*>(i);
375
376 if (paramDiff->load) {
377 if (paramDiff->noVehicleValue) {
378 _parameterMgr->_mavlinkParamSet(paramDiff->componentId, paramDiff->name, paramDiff->valueType, paramDiff->fileValueVar);
379 } else {
380 Fact* fact = _parameterMgr->getParameter(paramDiff->componentId, paramDiff->name);
381 fact->setRawValue(paramDiff->fileValueVar);
382 }
383 }
384 }
385}
386
388{
389 QFile file(filename);
390
391 if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
392 QGC::showAppMessage(tr("Unable to open file: %1").arg(filename));
393 return false;
394 }
395
396 clearDiff();
397
398 QTextStream stream(&file);
399
400 int firstComponentId = -1;
401 while (!stream.atEnd()) {
402 QString line = stream.readLine();
403 if (!line.startsWith("#")) {
404 QStringList wpParams = line.split("\t");
405 if (wpParams.size() == 5) {
406 int vehicleId = wpParams.at(0).toInt();
407 int componentId = wpParams.at(1).toInt();
408 QString paramName = wpParams.at(2);
409 QString fileValueStr = wpParams.at(3);
410 int mavParamType = wpParams.at(4).toInt();
411 QString vehicleValueStr;
412 QString units;
413 QVariant fileValueVar = fileValueStr;
414 bool noVehicleValue = false;
415 bool readOnly = false;
416
417 if (_vehicle->id() != vehicleId) {
418 _diffOtherVehicle = true;
419 }
420 if (firstComponentId == -1) {
421 firstComponentId = componentId;
422 } else if (firstComponentId != componentId) {
423 _diffMultipleComponents = true;
424 }
425
426 if (_parameterMgr->parameterExists(componentId, paramName)) {
427 Fact* vehicleFact = _parameterMgr->getParameter(componentId, paramName);
428 FactMetaData* vehicleFactMetaData = vehicleFact->metaData();
429 Fact* fileFact = new Fact(vehicleFact->componentId(), vehicleFact->name(), vehicleFact->type(), this);
430
431 // Turn off reboot messaging before setting value in fileFact
432 bool vehicleRebootRequired = vehicleFactMetaData->vehicleRebootRequired();
433 vehicleFactMetaData->setVehicleRebootRequired(false);
434 fileFact->setMetaData(vehicleFact->metaData());
435 fileFact->setRawValue(fileValueStr);
436 vehicleFactMetaData->setVehicleRebootRequired(vehicleRebootRequired);
437 readOnly = vehicleFact->readOnly();
438
439 if (vehicleFact->rawValue() == fileFact->rawValue()) {
440 continue;
441 }
442 fileValueStr = fileFact->enumOrValueString();
443 fileValueVar = fileFact->rawValue();
444 vehicleValueStr = vehicleFact->enumOrValueString();
445 units = vehicleFact->cookedUnits();
446 } else {
447 noVehicleValue = true;
448 }
449
450 if (!readOnly) {
451 ParameterEditorDiff* paramDiff = new ParameterEditorDiff(this);
452
453 paramDiff->componentId = componentId;
454 paramDiff->name = paramName;
455 paramDiff->valueType = ParameterManager::mavTypeToFactType(static_cast<MAV_PARAM_TYPE>(mavParamType));
456 paramDiff->fileValue = fileValueStr;
457 paramDiff->fileValueVar = fileValueVar;
458 paramDiff->vehicleValue = vehicleValueStr;
459 paramDiff->noVehicleValue = noVehicleValue;
460 paramDiff->units = units;
461
462 _diffList.append(paramDiff);
463 }
464 }
465 }
466 }
467
468 file.close();
469
470 emit diffOtherVehicleChanged(_diffOtherVehicle);
471 emit diffMultipleComponentsChanged(_diffMultipleComponents);
472
473 return true;
474}
475
477{
478 _parameterMgr->refreshAllParameters();
479}
480
486
492
493bool ParameterEditorController::_shouldShow(Fact* fact) const
494{
495 if (_hideReadOnly && fact->readOnly()) {
496 return false;
497 }
498 if (_showModifiedOnly) {
499 if (!fact->defaultValueAvailable() || fact->valueEqualsDefault()) {
500 return false;
501 }
502 }
503 if (_showFavoritesOnly) {
504 if (!_favoriteNames.contains(fact->name())) {
505 return false;
506 }
507 }
508 return true;
509}
510
511void ParameterEditorController::_searchTextChanged(void)
512{
513 _searchTimer.start();
514}
515
516void ParameterEditorController::_hideReadOnlyChanged(void)
517{
518 _buildLists();
519
520 ParameterEditorCategory* category = _categories.count() ? _categories.value<ParameterEditorCategory*>(0) : nullptr;
521 setCurrentCategory(category);
522
523 // Re-trigger search if active
524 if (!_searchText.isEmpty() || _showModifiedOnly) {
525 _performSearch();
526 }
527}
528
529void ParameterEditorController::_performSearch(void)
530{
531 QObjectList newParameterList;
532
533 QStringList rgSearchStrings = _searchText.split(' ', Qt::SkipEmptyParts);
534
535 if (rgSearchStrings.isEmpty() && !_showModifiedOnly && !_showFavoritesOnly) {
536 ParameterEditorCategory* category = _categories.count() ? _categories.value<ParameterEditorCategory*>(0) : nullptr;
537 setCurrentCategory(category);
538 _searchParameters.clear();
539 } else {
540 QVector<QRegularExpression> regexList;
541 regexList.reserve(rgSearchStrings.size());
542 for (const QString &searchItem : rgSearchStrings) {
543 QRegularExpression re(searchItem, QRegularExpression::CaseInsensitiveOption);
544 regexList.append(re.isValid() ? re : QRegularExpression());
545 }
546
547 _searchParameters.beginReset();
548 _searchParameters.clear();
549
550 for (int compId : _parameterMgr->componentIds()) {
551 for (const QString &paraName: _parameterMgr->parameterNames(compId)) {
552 Fact* fact = _parameterMgr->getParameter(compId, paraName);
553 bool matched = _shouldShow(fact);
554 // All of the search items must match in order for the parameter to be added to the list
555 if (matched) {
556 for (int i = 0; i < rgSearchStrings.size(); ++i) {
557 const QRegularExpression &re = regexList.at(i);
558 if (re.isValid()) {
559 if (!fact->name().contains(re) &&
560 !fact->shortDescription().contains(re) &&
561 !fact->longDescription().contains(re)) {
562 matched = false;
563 }
564 } else {
565 const QString &searchItem = rgSearchStrings.at(i);
566 if (!fact->name().contains(searchItem, Qt::CaseInsensitive) &&
567 !fact->shortDescription().contains(searchItem, Qt::CaseInsensitive) &&
568 !fact->longDescription().contains(searchItem, Qt::CaseInsensitive)) {
569 matched = false;
570 }
571 }
572 }
573 }
574 if (matched) {
575 _searchParameters.append(fact);
576 }
577 }
578 }
579
580 _searchParameters.endReset();
581
582 if (_parameters != &_searchParameters) {
583 _parameters = &_searchParameters;
584 emit parametersChanged();
585
586 _currentCategory = nullptr;
587 _currentGroup = nullptr;
588 }
589 }
590}
591
592void ParameterEditorController::_currentCategoryChanged(void)
593{
594 ParameterEditorGroup* group = nullptr;
595 if (_currentCategory) {
596 // Select first group when category changes
597 group = _currentCategory->groups.value<ParameterEditorGroup*>(0);
598 } else {
599 group = nullptr;
600 }
601 setCurrentGroup(group);
602}
603
604void ParameterEditorController::_currentGroupChanged(void)
605{
606 _parameters = _currentGroup ? &_currentGroup->facts : nullptr;
607 emit parametersChanged();
608}
609
611{
612 ParameterEditorCategory* category = qobject_cast<ParameterEditorCategory*>(currentCategory);
613 if (category != _currentCategory) {
614 _currentCategory = category;
616 }
617}
618
620{
621 ParameterEditorGroup* group = qobject_cast<ParameterEditorGroup*>(currentGroup);
622 if (group != _currentGroup) {
623 _currentGroup = group;
624 emit currentGroupChanged();
625 }
626}
627
629{
630 QStringList list(_favoriteNames.begin(), _favoriteNames.end());
631 list.sort();
632 return list;
633}
634
635void ParameterEditorController::toggleFavorite(const QString& paramName)
636{
637 if (_favoriteNames.contains(paramName)) {
638 _favoriteNames.remove(paramName);
639 } else {
640 _favoriteNames.insert(paramName);
641 }
642 _saveFavorites();
643 emit favoritesChanged();
644
645 if (_showFavoritesOnly) {
646 _performSearch();
647 }
648}
649
650bool ParameterEditorController::isFavorite(const QString& paramName) const
651{
652 return _favoriteNames.contains(paramName);
653}
654
656{
657 _favoriteNames.clear();
658 _saveFavorites();
659 emit favoritesChanged();
660
661 if (_showFavoritesOnly) {
662 _performSearch();
663 }
664}
665
666void ParameterEditorController::_loadFavorites()
667{
668 Fact* fact = SettingsManager::instance()->appSettings()->favoriteParameters();
669 const QStringList list = fact->rawValue().toString().split(",", Qt::SkipEmptyParts);
670 _favoriteNames = QSet<QString>(list.begin(), list.end());
671}
672
673void ParameterEditorController::_saveFavorites()
674{
675 QStringList list(_favoriteNames.begin(), _favoriteNames.end());
676 list.sort();
677 Fact* fact = SettingsManager::instance()->appSettings()->favoriteParameters();
678 fact->setRawValue(list.join(","));
679}
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static constexpr const char * parameterFileExtension
Holds the meta data associated with a Fact.
static constexpr const char * kDefaultGroup
static constexpr const char * kDefaultCategory
void setVehicleRebootRequired(bool rebootRequired)
bool vehicleRebootRequired() const
Used for handling missing Facts from C++ code.
A Fact is used to hold a single value within the system.
Definition Fact.h:17
QString enumOrValueString()
Definition Fact.cc:784
void setMetaData(FactMetaData *metaData, bool setDefaultFromMetaData=false)
Definition Fact.cc:674
QString cookedUnits() const
Definition Fact.cc:514
QString longDescription() const
Definition Fact.cc:494
QString shortDescription() const
Definition Fact.cc:474
FactMetaData * metaData()
Definition Fact.h:171
bool valueEqualsDefault() const
Definition Fact.cc:683
bool readOnly() const
Definition Fact.cc:828
int componentId() const
Definition Fact.h:90
QString group() const
Definition Fact.cc:664
FactMetaData::ValueType_t type() const
Definition Fact.h:124
void setRawValue(const QVariant &value)
Definition Fact.cc:128
bool defaultValueAvailable() const
Definition Fact.cc:697
QString name() const
Definition Fact.h:121
QString category() const
Definition Fact.cc:654
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
QMap< QString, ParameterEditorGroup * > mapGroupName2Group
Q_INVOKABLE void resetAllToVehicleConfiguration(void)
void showFavoritesOnlyChanged(void)
Q_INVOKABLE bool buildDiffFromFile(const QString &filename)
void diffMultipleComponentsChanged(bool diffMultipleComponents)
Q_INVOKABLE void toggleFavorite(const QString &paramName)
Q_INVOKABLE void clearAllFavorites(void)
QStringList favoriteParameterNames(void) const
void setCurrentGroup(QObject *currentGroup)
Q_INVOKABLE void saveToFile(const QString &filename)
ParameterEditorController(QObject *parent=nullptr)
void searchTextChanged(QString searchText)
void currentCategoryChanged(void)
void diffOtherVehicleChanged(bool diffOtherVehicle)
void setCurrentCategory(QObject *currentCategory)
Q_INVOKABLE bool isFavorite(const QString &paramName) const
void showModifiedOnlyChanged(void)
Q_INVOKABLE void resetAllToDefaults(void)
FactMetaData::ValueType_t valueType
bool parameterExists(int componentId, const QString &paramName) const
Fact * getParameter(int componentId, const QString &paramName)
void factAdded(int componentId, Fact *fact)
static FactMetaData::ValueType_t mavTypeToFactType(MAV_PARAM_TYPE mavType)
void refreshAllParameters(uint8_t componentID)
Re-request the full set of parameters from the autopilot.
void resetAllToVehicleConfiguration()
void writeParametersToStream(QTextStream &stream) const
QVector< QVariant > ColumnData
void insert(int row, Fact *fact)
int rowCount(const QModelIndex &parent=QModelIndex()) const override
int columnCount(const QModelIndex &parent=QModelIndex()) const override
QVariant headerData(int section, Qt::Orientation orientation, int role=Qt::DisplayRole) const override
QVariant data(const QModelIndex &index, int role=Qt::DisplayRole) const override
QHash< int, QByteArray > roleNames(void) const override
void rowCountChanged(int count)
void endReset()
Supports nesting - only outermost call has effect.
void beginReset()
Supports nesting - only outermost call has effect.
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
T value(int index) const
QObject * removeAt(int index)
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
void insert(int index, QObject *object)
static SettingsManager * instance()
AppSettings * appSettings() const
int id() const
Definition Vehicle.h:425
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Definition AppMessages.cc:9