13 : QAbstractTableModel(parent)
25 return _tableData.count();
30 return _tableViewColCount;
35 if (!index.isValid()) {
39 if (index.row() < 0 || index.row() >= _tableData.count()) {
42 if (index.column() < 0 || index.column() >= _tableViewColCount) {
48 return QVariant::fromValue(_tableData[index.row()][index.column()]);
50 return QVariant::fromValue(_tableData[index.row()][
ValueColumn]);
58 if (orientation != Qt::Horizontal || role != Qt::DisplayRole) {
67 default:
return QVariant();
74 {Qt::DisplayRole,
"display"},
94 qWarning() <<
"Invalid row row:rowCount" << row <<
rowCount() << Q_FUNC_INFO;
95 row = qMax(qMin(row,
rowCount()), 0);
98 ColumnData colData(_tableViewColCount, QString());
104 if (!_isResetting()) {
105 beginInsertRows(QModelIndex(), row, row);
107 _tableData.insert(row, colData);
108 if (!_isResetting()) {
116 _resetNestingCount++;
118 if (_resetNestingCount == 1) {
125 if (_resetNestingCount == 0) {
126 qWarning() <<
"ParameterTableModel::endReset called without prior beginReset";
129 _resetNestingCount--;
130 if (_resetNestingCount == 0) {
138 if (row < 0 || row >= _tableData.count()) {
139 qWarning() <<
"Invalid row row:rowCount" << row << _tableData.count() << Q_FUNC_INFO;
155 , _parameterMgr(_vehicle->parameterManager())
161 _searchTimer.setSingleShot(
true);
162 _searchTimer.setInterval(300);
170 connect(&_searchTimer, &QTimer::timeout,
this, &ParameterEditorController::_performSearch);
184void ParameterEditorController::_buildListsForComponent(
int compId)
186 for (
const QString& factName: _parameterMgr->parameterNames(compId)) {
189 if (_hideReadOnly && fact->
readOnly()) {
194 if (_mapCategoryName2Category.contains(fact->
category())) {
195 category = _mapCategoryName2Category[fact->
category()];
199 _mapCategoryName2Category[fact->
category()] = category;
200 _categories.
append(category);
218void ParameterEditorController::_buildLists(
void)
220 _currentCategory =
nullptr;
221 _currentGroup =
nullptr;
222 _parameters =
nullptr;
223 _mapCategoryName2Category.clear();
228 _buildListsForComponent(MAV_COMP_ID_AUTOPILOT1);
231 for (
int i=0; i<_categories.
count(); i++) {
233 if (category->
name ==
"Standard" && i != 0) {
235 _categories.
insert(0, category);
241 for (
int i=0; i<_categories.
count(); i++) {
244 if (i != _categories.
count() - 1) {
246 _categories.
append(category);
253 for (
int compId: _parameterMgr->componentIds()) {
254 if (compId != MAV_COMP_ID_AUTOPILOT1) {
255 _buildListsForComponent(compId);
260 for (
int i=0; i<_categories.
count(); i++) {
265 if (j != _categories.
count() - 1) {
275void ParameterEditorController::_factAdded(
int compId,
Fact* fact)
277 if (_hideReadOnly && fact->
readOnly()) {
281 bool inserted =
false;
284 if (_mapCategoryName2Category.contains(fact->
category())) {
285 category = _mapCategoryName2Category[fact->
category()];
289 _mapCategoryName2Category[fact->
category()] = category;
293 for (
int i=0; i<_categories.
count(); i++) {
295 _categories.
insert(i, category);
301 _categories.
append(category);
317 for (
int i=0; i<groups.
count(); i++) {
330 auto& facts = group->
facts;
331 for (
int i=0; i<facts.rowCount(); i++) {
332 if (facts.factAt(i)->name() > fact->
name()) {
342 if (!filename.isEmpty()) {
343 QString parameterFilename = filename;
344 if (!QFileInfo(filename).fileName().contains(
".")) {
348 QFile file(parameterFilename);
350 if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
355 QTextStream stream(&file);
364 _diffOtherVehicle =
false;
365 _diffMultipleComponents =
false;
373 for (
int i=0; i<_diffList.
count(); i++) {
376 if (paramDiff->
load) {
389 QFile file(filename);
391 if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
398 QTextStream stream(&file);
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;
413 QVariant fileValueVar = fileValueStr;
414 bool noVehicleValue =
false;
415 bool readOnly =
false;
418 _diffOtherVehicle =
true;
420 if (firstComponentId == -1) {
421 firstComponentId = componentId;
422 }
else if (firstComponentId != componentId) {
423 _diffMultipleComponents =
true;
443 fileValueVar = fileFact->
rawValue();
447 noVehicleValue =
true;
454 paramDiff->
name = paramName;
460 paramDiff->
units = units;
462 _diffList.
append(paramDiff);
493bool ParameterEditorController::_shouldShow(
Fact* fact)
const
495 if (_hideReadOnly && fact->
readOnly()) {
498 if (_showModifiedOnly) {
503 if (_showFavoritesOnly) {
504 if (!_favoriteNames.contains(fact->
name())) {
511void ParameterEditorController::_searchTextChanged(
void)
513 _searchTimer.start();
516void ParameterEditorController::_hideReadOnlyChanged(
void)
524 if (!_searchText.isEmpty() || _showModifiedOnly) {
529void ParameterEditorController::_performSearch(
void)
531 QObjectList newParameterList;
533 QStringList rgSearchStrings = _searchText.split(
' ', Qt::SkipEmptyParts);
535 if (rgSearchStrings.isEmpty() && !_showModifiedOnly && !_showFavoritesOnly) {
538 _searchParameters.
clear();
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());
548 _searchParameters.
clear();
550 for (
int compId : _parameterMgr->componentIds()) {
551 for (
const QString ¶Name: _parameterMgr->parameterNames(compId)) {
553 bool matched = _shouldShow(fact);
556 for (
int i = 0; i < rgSearchStrings.size(); ++i) {
557 const QRegularExpression &re = regexList.at(i);
559 if (!fact->
name().contains(re) &&
565 const QString &searchItem = rgSearchStrings.at(i);
566 if (!fact->
name().contains(searchItem, Qt::CaseInsensitive) &&
575 _searchParameters.
append(fact);
582 if (_parameters != &_searchParameters) {
583 _parameters = &_searchParameters;
586 _currentCategory =
nullptr;
587 _currentGroup =
nullptr;
592void ParameterEditorController::_currentCategoryChanged(
void)
595 if (_currentCategory) {
604void ParameterEditorController::_currentGroupChanged(
void)
606 _parameters = _currentGroup ? &_currentGroup->
facts :
nullptr;
613 if (category != _currentCategory) {
614 _currentCategory = category;
622 if (group != _currentGroup) {
623 _currentGroup = group;
630 QStringList list(_favoriteNames.begin(), _favoriteNames.end());
637 if (_favoriteNames.contains(paramName)) {
638 _favoriteNames.remove(paramName);
640 _favoriteNames.insert(paramName);
645 if (_showFavoritesOnly) {
652 return _favoriteNames.contains(paramName);
657 _favoriteNames.clear();
661 if (_showFavoritesOnly) {
666void ParameterEditorController::_loadFavorites()
669 const QStringList list = fact->
rawValue().toString().split(
",", Qt::SkipEmptyParts);
670 _favoriteNames = QSet<QString>(list.begin(), list.end());
673void ParameterEditorController::_saveFavorites()
675 QStringList list(_favoriteNames.begin(), _favoriteNames.end());
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static constexpr const char * parameterFileExtension
Used for handling missing Facts from C++ code.
A Fact is used to hold a single value within the system.
QString enumOrValueString()
void setMetaData(FactMetaData *metaData, bool setDefaultFromMetaData=false)
QString cookedUnits() const
QString longDescription() const
QString shortDescription() const
FactMetaData * metaData()
bool valueEqualsDefault() const
FactMetaData::ValueType_t type() const
void setRawValue(const QVariant &value)
bool defaultValueAvailable() const
QVariant rawValue() const
Value after translation.
QMap< QString, ParameterEditorGroup * > mapGroupName2Group
QmlObjectListModel groups
Q_INVOKABLE void resetAllToVehicleConfiguration(void)
void showFavoritesOnlyChanged(void)
Q_INVOKABLE bool buildDiffFromFile(const QString &filename)
void parametersChanged(void)
Q_INVOKABLE void refresh(void)
void currentGroupChanged(void)
void diffMultipleComponentsChanged(bool diffMultipleComponents)
Q_INVOKABLE void toggleFavorite(const QString ¶mName)
QObject * currentCategory(void)
Q_INVOKABLE void clearAllFavorites(void)
~ParameterEditorController()
QStringList favoriteParameterNames(void) const
void setCurrentGroup(QObject *currentGroup)
Q_INVOKABLE void saveToFile(const QString &filename)
ParameterEditorController(QObject *parent=nullptr)
void searchTextChanged(QString searchText)
Q_INVOKABLE void sendDiff(void)
void currentCategoryChanged(void)
void diffOtherVehicleChanged(bool diffOtherVehicle)
void setCurrentCategory(QObject *currentCategory)
void favoritesChanged(void)
Q_INVOKABLE bool isFavorite(const QString ¶mName) const
Q_INVOKABLE void clearDiff(void)
void showModifiedOnlyChanged(void)
QObject * currentGroup(void)
Q_INVOKABLE void resetAllToDefaults(void)
void hideReadOnlyChanged(void)
FactMetaData::ValueType_t valueType
ParameterEditorGroup(QObject *parent)
ParameterTableModel facts
bool parameterExists(int componentId, const QString ¶mName) const
Fact * getParameter(int componentId, const QString ¶mName)
void factAdded(int componentId, Fact *fact)
static FactMetaData::ValueType_t mavTypeToFactType(MAV_PARAM_TYPE mavType)
void resetAllParametersToDefaults()
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
~ParameterTableModel() override
void rowCountChanged(int count)
void endReset()
Supports nesting - only outermost call has effect.
void beginReset()
Supports nesting - only outermost call has effect.
Fact * factAt(int row) const
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
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
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.