QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ParameterEditorController.cc
Go to the documentation of this file.
2#include "QGCApplication.h"
3#include "ParameterManager.h"
4#include "AppSettings.h"
5#include "Vehicle.h"
7
8QGC_LOGGING_CATEGORY(ParameterEditorControllerLog, "QMLControls.ParameterEditorController")
9
11 : QAbstractTableModel(parent)
12{
13
14}
15
20
21int ParameterTableModel::rowCount(const QModelIndex& /*parent*/) const
22{
23 return _tableData.count();
24}
25
26int ParameterTableModel::columnCount(const QModelIndex & /*parent*/) const
27{
28 return _tableViewColCount;
29}
30
31QVariant ParameterTableModel::data(const QModelIndex &index, int role) const
32{
33 if (!index.isValid()) {
34 return QVariant();
35 }
36
37 if (index.row() < 0 || index.row() >= _tableData.count()) {
38 return QVariant();
39 }
40 if (index.column() < 0 || index.column() >= _tableViewColCount) {
41 return QVariant();
42 }
43
44 switch (role) {
45 case Qt::DisplayRole:
46 return QVariant::fromValue(_tableData[index.row()][index.column()]);
47 case FactRole:
48 return QVariant::fromValue(_tableData[index.row()][ValueColumn]);
49 default:
50 return QVariant();
51 }
52}
53
54QHash<int, QByteArray> ParameterTableModel::roleNames() const
55{
56 return {
57 {Qt::DisplayRole, "display"},
58 {FactRole, "fact"}
59 };
60}
61
63{
64 beginReset();
65 _tableData.clear();
66 endReset();
67}
68
70{
71 insert(rowCount(), fact);
72}
73
75{
76 if (row < 0 || row > rowCount()) {
77 qWarning() << "Invalid row row:rowCount" << row << rowCount() << Q_FUNC_INFO;
78 row = qMax(qMin(row, rowCount()), 0);
79 }
80
81 ColumnData colData(_tableViewColCount, QString());
82 colData[NameColumn] = fact->name();
83 colData[ValueColumn] = QVariant::fromValue(fact);
84 colData[DescriptionColumn] = fact->shortDescription();
85
86 if (!_isResetting()) {
87 beginInsertRows(QModelIndex(), row, row);
88 }
89 _tableData.insert(row, colData);
90 if (!_isResetting()) {
91 endInsertRows();
93 }
94}
95
97{
98 _resetNestingCount++;
99
100 if (_resetNestingCount == 1) {
101 beginResetModel();
102 }
103}
104
106{
107 if (_resetNestingCount == 0) {
108 qWarning() << "ParameterTableModel::endReset called without prior beginReset";
109 return;
110 }
111 _resetNestingCount--;
112 if (_resetNestingCount == 0) {
113 endResetModel();
115 }
116}
117
119{
120 if (row < 0 || row >= _tableData.count()) {
121 qWarning() << "Invalid row row:rowCount" << row << _tableData.count() << Q_FUNC_INFO;
122 return nullptr;
123 }
124
125 return _tableData[row][ValueColumn].value<Fact*>();
126}
127
128
130 : QObject(parent)
131{
132
133}
134
135ParameterEditorController::ParameterEditorController(QObject *parent)
136 : FactPanelController(parent)
137 , _parameterMgr(_vehicle->parameterManager())
138{
139 // qCDebug(ParameterEditorControllerLog) << Q_FUNC_INFO << this;
140
141 _buildLists();
142
143 _searchTimer.setSingleShot(true);
144 _searchTimer.setInterval(300);
145
146 connect(this, &ParameterEditorController::currentCategoryChanged, this, &ParameterEditorController::_currentCategoryChanged);
147 connect(this, &ParameterEditorController::currentGroupChanged, this, &ParameterEditorController::_currentGroupChanged);
148 connect(this, &ParameterEditorController::searchTextChanged, this, &ParameterEditorController::_searchTextChanged);
149 connect(this, &ParameterEditorController::showModifiedOnlyChanged, this, &ParameterEditorController::_searchTextChanged);
150 connect(&_searchTimer, &QTimer::timeout, this, &ParameterEditorController::_performSearch);
151 connect(_parameterMgr, &ParameterManager::factAdded, this, &ParameterEditorController::_factAdded);
152
153 ParameterEditorCategory* category = _categories.count() ? _categories.value<ParameterEditorCategory*>(0) : nullptr;
154 setCurrentCategory(category);
155}
156
157ParameterEditorController::~ParameterEditorController()
158{
159 // qCDebug(ParameterEditorControllerLog) << Q_FUNC_INFO << this;
160}
161
162void ParameterEditorController::_buildListsForComponent(int compId)
163{
164 for (const QString& factName: _parameterMgr->parameterNames(compId)) {
165 Fact* fact = _parameterMgr->getParameter(compId, factName);
166
167 ParameterEditorCategory* category = nullptr;
168 if (_mapCategoryName2Category.contains(fact->category())) {
169 category = _mapCategoryName2Category[fact->category()];
170 } else {
171 category = new ParameterEditorCategory(this);
172 category->name = fact->category();
173 _mapCategoryName2Category[fact->category()] = category;
174 _categories.append(category);
175 }
176
177 ParameterEditorGroup* group = nullptr;
178 if (category->mapGroupName2Group.contains(fact->group())) {
179 group = category->mapGroupName2Group[fact->group()];
180 } else {
181 group = new ParameterEditorGroup(this);
182 group->componentId = compId;
183 group->name = fact->group();
184 category->mapGroupName2Group[fact->group()] = group;
185 category->groups.append(group);
186 }
187
188 group->facts.append(fact);
189 }
190}
191
192void ParameterEditorController::_buildLists(void)
193{
194 // Autopilot component should always be first list
195 _buildListsForComponent(MAV_COMP_ID_AUTOPILOT1);
196
197 // "Standard" category should always be first
198 for (int i=0; i<_categories.count(); i++) {
199 ParameterEditorCategory* category = _categories.value<ParameterEditorCategory*>(i);
200 if (category->name == "Standard" && i != 0) {
201 _categories.removeAt(i);
202 _categories.insert(0, category);
203 break;
204 }
205 }
206
207 // Default category should always be last
208 for (int i=0; i<_categories.count(); i++) {
209 ParameterEditorCategory* category = _categories.value<ParameterEditorCategory*>(i);
210 if (category->name == FactMetaData::kDefaultCategory) {
211 if (i != _categories.count() - 1) {
212 _categories.removeAt(i);
213 _categories.append(category);
214 }
215 break;
216 }
217 }
218
219 // Now add other random components
220 for (int compId: _parameterMgr->componentIds()) {
221 if (compId != MAV_COMP_ID_AUTOPILOT1) {
222 _buildListsForComponent(compId);
223 }
224 }
225
226 // Default group should always be last
227 for (int i=0; i<_categories.count(); i++) {
228 ParameterEditorCategory* category = _categories.value<ParameterEditorCategory*>(i);
229 for (int j=0; j<category->groups.count(); j++) {
231 if (group->name == FactMetaData::kDefaultGroup) {
232 if (j != _categories.count() - 1) {
233 category->groups.removeAt(j);
234 category->groups.append(group);
235 }
236 break;
237 }
238 }
239 }
240}
241
242void ParameterEditorController::_factAdded(int compId, Fact* fact)
243{
244 bool inserted = false;
245 ParameterEditorCategory* category = nullptr;
246
247 if (_mapCategoryName2Category.contains(fact->category())) {
248 category = _mapCategoryName2Category[fact->category()];
249 } else {
250 category = new ParameterEditorCategory(this);
251 category->name = fact->category();
252 _mapCategoryName2Category[fact->category()] = category;
253
254 // Insert in sorted order
255 inserted = false;
256 for (int i=0; i<_categories.count(); i++) {
257 if (_categories.value<ParameterEditorCategory*>(i)->name > category->name) {
258 _categories.insert(i, category);
259 inserted = true;
260 break;
261 }
262 }
263 if (!inserted) {
264 _categories.append(category);
265 }
266 }
267
268 ParameterEditorGroup* group = nullptr;
269 if (category->mapGroupName2Group.contains(fact->group())) {
270 group = category->mapGroupName2Group[fact->group()];
271 } else {
272 group = new ParameterEditorGroup(this);
273 group->componentId = compId;
274 group->name = fact->group();
275 category->mapGroupName2Group[fact->group()] = group;
276
277 // Insert in sorted order
278 QmlObjectListModel& groups = category->groups;
279 inserted = false;
280 for (int i=0; i<groups.count(); i++) {
281 if (groups.value<ParameterEditorGroup*>(i)->name > group->name) {
282 groups.insert(i, group);
283 inserted = true;
284 break;
285 }
286 }
287 if (!inserted) {
288 groups.append(group);
289 }
290 }
291
292 // Insert in sorted order
293 auto& facts = group->facts;
294 for (int i=0; i<facts.rowCount(); i++) {
295 if (facts.factAt(i)->name() > fact->name()) {
296 facts.insert(i, fact);
297 return;
298 }
299 }
300 facts.append(fact);
301}
302
303void ParameterEditorController::saveToFile(const QString& filename)
304{
305 if (!filename.isEmpty()) {
306 QString parameterFilename = filename;
307 if (!QFileInfo(filename).fileName().contains(".")) {
308 parameterFilename += QString(".%1").arg(AppSettings::parameterFileExtension);
309 }
310
311 QFile file(parameterFilename);
312
313 if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
314 qgcApp()->showAppMessage(tr("Unable to create file: %1").arg(parameterFilename));
315 return;
316 }
317
318 QTextStream stream(&file);
319 _parameterMgr->writeParametersToStream(stream);
320 file.close();
321 }
322}
323
324void ParameterEditorController::clearDiff(void)
325{
326 _diffList.clearAndDeleteContents();
327 _diffOtherVehicle = false;
328 _diffMultipleComponents = false;
329
330 emit diffOtherVehicleChanged(_diffOtherVehicle);
331 emit diffMultipleComponentsChanged(_diffMultipleComponents);
332}
333
334void ParameterEditorController::sendDiff(void)
335{
336 for (int i=0; i<_diffList.count(); i++) {
337 ParameterEditorDiff* paramDiff = _diffList.value<ParameterEditorDiff*>(i);
338
339 if (paramDiff->load) {
340 if (paramDiff->noVehicleValue) {
341 _parameterMgr->_mavlinkParamSet(paramDiff->componentId, paramDiff->name, paramDiff->valueType, paramDiff->fileValueVar);
342 } else {
343 Fact* fact = _parameterMgr->getParameter(paramDiff->componentId, paramDiff->name);
344 fact->setRawValue(paramDiff->fileValueVar);
345 }
346 }
347 }
348}
349
350bool ParameterEditorController::buildDiffFromFile(const QString& filename)
351{
352 QFile file(filename);
353
354 if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
355 qgcApp()->showAppMessage(tr("Unable to open file: %1").arg(filename));
356 return false;
357 }
358
359 clearDiff();
360
361 QTextStream stream(&file);
362
363 int firstComponentId = -1;
364 while (!stream.atEnd()) {
365 QString line = stream.readLine();
366 if (!line.startsWith("#")) {
367 QStringList wpParams = line.split("\t");
368 if (wpParams.size() == 5) {
369 int vehicleId = wpParams.at(0).toInt();
370 int componentId = wpParams.at(1).toInt();
371 QString paramName = wpParams.at(2);
372 QString fileValueStr = wpParams.at(3);
373 int mavParamType = wpParams.at(4).toInt();
374 QString vehicleValueStr;
375 QString units;
376 QVariant fileValueVar = fileValueStr;
377 bool noVehicleValue = false;
378 bool readOnly = false;
379
380 if (_vehicle->id() != vehicleId) {
381 _diffOtherVehicle = true;
382 }
383 if (firstComponentId == -1) {
384 firstComponentId = componentId;
385 } else if (firstComponentId != componentId) {
386 _diffMultipleComponents = true;
387 }
388
389 if (_parameterMgr->parameterExists(componentId, paramName)) {
390 Fact* vehicleFact = _parameterMgr->getParameter(componentId, paramName);
391 FactMetaData* vehicleFactMetaData = vehicleFact->metaData();
392 Fact* fileFact = new Fact(vehicleFact->componentId(), vehicleFact->name(), vehicleFact->type(), this);
393
394 // Turn off reboot messaging before setting value in fileFact
395 bool vehicleRebootRequired = vehicleFactMetaData->vehicleRebootRequired();
396 vehicleFactMetaData->setVehicleRebootRequired(false);
397 fileFact->setMetaData(vehicleFact->metaData());
398 fileFact->setRawValue(fileValueStr);
399 vehicleFactMetaData->setVehicleRebootRequired(vehicleRebootRequired);
400 readOnly = vehicleFact->readOnly();
401
402 if (vehicleFact->rawValue() == fileFact->rawValue()) {
403 continue;
404 }
405 fileValueStr = fileFact->enumOrValueString();
406 fileValueVar = fileFact->rawValue();
407 vehicleValueStr = vehicleFact->enumOrValueString();
408 units = vehicleFact->cookedUnits();
409 } else {
410 noVehicleValue = true;
411 }
412
413 if (!readOnly) {
414 ParameterEditorDiff* paramDiff = new ParameterEditorDiff(this);
415
416 paramDiff->componentId = componentId;
417 paramDiff->name = paramName;
418 paramDiff->valueType = ParameterManager::mavTypeToFactType(static_cast<MAV_PARAM_TYPE>(mavParamType));
419 paramDiff->fileValue = fileValueStr;
420 paramDiff->fileValueVar = fileValueVar;
421 paramDiff->vehicleValue = vehicleValueStr;
422 paramDiff->noVehicleValue = noVehicleValue;
423 paramDiff->units = units;
424
425 _diffList.append(paramDiff);
426 }
427 }
428 }
429 }
430
431 file.close();
432
433 emit diffOtherVehicleChanged(_diffOtherVehicle);
434 emit diffMultipleComponentsChanged(_diffMultipleComponents);
435
436 return true;
437}
438
439void ParameterEditorController::refresh(void)
440{
441 _parameterMgr->refreshAllParameters();
442}
443
444void ParameterEditorController::resetAllToDefaults(void)
445{
446 _parameterMgr->resetAllParametersToDefaults();
447 refresh();
448}
449
450void ParameterEditorController::resetAllToVehicleConfiguration(void)
451{
452 _parameterMgr->resetAllToVehicleConfiguration();
453 refresh();
454}
455
456bool ParameterEditorController::_shouldShow(Fact* fact) const
457{
458 if (!_showModifiedOnly) {
459 return true;
460 }
461
462 return fact->defaultValueAvailable() && !fact->valueEqualsDefault();
463}
464
465void ParameterEditorController::_searchTextChanged(void)
466{
467 _searchTimer.start();
468}
469
470void ParameterEditorController::_performSearch(void)
471{
472 QObjectList newParameterList;
473
474 QStringList rgSearchStrings = _searchText.split(' ', Qt::SkipEmptyParts);
475
476 if (rgSearchStrings.isEmpty() && !_showModifiedOnly) {
477 ParameterEditorCategory* category = _categories.count() ? _categories.value<ParameterEditorCategory*>(0) : nullptr;
478 setCurrentCategory(category);
479 _searchParameters.clear();
480 } else {
481 QVector<QRegularExpression> regexList;
482 regexList.reserve(rgSearchStrings.size());
483 for (const QString &searchItem : rgSearchStrings) {
484 QRegularExpression re(searchItem, QRegularExpression::CaseInsensitiveOption);
485 regexList.append(re.isValid() ? re : QRegularExpression());
486 }
487
488 _searchParameters.beginReset();
489 _searchParameters.clear();
490
491 for (const QString &paraName: _parameterMgr->parameterNames(_vehicle->defaultComponentId())) {
492 Fact* fact = _parameterMgr->getParameter(_vehicle->defaultComponentId(), paraName);
493 bool matched = _shouldShow(fact);
494 // All of the search items must match in order for the parameter to be added to the list
495 if (matched) {
496 for (int i = 0; i < rgSearchStrings.size(); ++i) {
497 const QRegularExpression &re = regexList.at(i);
498 if (re.isValid()) {
499 if (!fact->name().contains(re) &&
500 !fact->shortDescription().contains(re) &&
501 !fact->longDescription().contains(re)) {
502 matched = false;
503 }
504 } else {
505 const QString &searchItem = rgSearchStrings.at(i);
506 if (!fact->name().contains(searchItem, Qt::CaseInsensitive) &&
507 !fact->shortDescription().contains(searchItem, Qt::CaseInsensitive) &&
508 !fact->longDescription().contains(searchItem, Qt::CaseInsensitive)) {
509 matched = false;
510 }
511 }
512 }
513 }
514 if (matched) {
515 _searchParameters.append(fact);
516 }
517 }
518
519 _searchParameters.endReset();
520
521 if (_parameters != &_searchParameters) {
522 _parameters = &_searchParameters;
523 emit parametersChanged();
524
525 _currentCategory = nullptr;
526 _currentGroup = nullptr;
527 }
528 }
529}
530
531void ParameterEditorController::_currentCategoryChanged(void)
532{
533 ParameterEditorGroup* group = nullptr;
534 if (_currentCategory) {
535 // Select first group when category changes
536 group = _currentCategory->groups.value<ParameterEditorGroup*>(0);
537 } else {
538 group = nullptr;
539 }
540 setCurrentGroup(group);
541}
542
543void ParameterEditorController::_currentGroupChanged(void)
544{
545 _parameters = _currentGroup ? &_currentGroup->facts : nullptr;
546 emit parametersChanged();
547}
548
549void ParameterEditorController::setCurrentCategory(QObject* currentCategory)
550{
551 ParameterEditorCategory* category = qobject_cast<ParameterEditorCategory*>(currentCategory);
552 if (category != _currentCategory) {
553 _currentCategory = category;
555 }
556}
557
558void ParameterEditorController::setCurrentGroup(QObject* currentGroup)
559{
560 ParameterEditorGroup* group = qobject_cast<ParameterEditorGroup*>(currentGroup);
561 if (group != _currentGroup) {
562 _currentGroup = group;
563 emit currentGroupChanged();
564 }
565}
#define qgcApp()
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static constexpr const char * parameterFileExtension
Definition AppSettings.h:88
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:19
QMap< QString, ParameterEditorGroup * > mapGroupName2Group
void diffMultipleComponentsChanged(bool diffMultipleComponents)
void searchTextChanged(QString searchText)
void currentCategoryChanged(void)
void diffOtherVehicleChanged(bool diffOtherVehicle)
void showModifiedOnlyChanged(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=MAV_COMP_ID_ALL)
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 rowCount READ rowCount NOTIFY rowCountChanged void append(Fact *fact)
int columnCount(const QModelIndex &parent=QModelIndex()) 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)
int id() const
Definition Vehicle.h:425
int defaultComponentId() const
Definition Vehicle.h:711