Browse Source

Support editing non-default component parameters

QGC4.4
Don Gagne 7 years ago
parent
commit
5332ca14c9
  1. 65
      src/QmlControls/ParameterEditorController.cc
  2. 4
      src/QmlControls/ParameterEditorController.h

65
src/QmlControls/ParameterEditorController.cc

@ -7,10 +7,6 @@ @@ -7,10 +7,6 @@
*
****************************************************************************/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "ParameterEditorController.h"
#include "QGCApplication.h"
#include "ParameterManager.h"
@ -25,18 +21,26 @@ @@ -25,18 +21,26 @@
#include <QStandardPaths>
/// @Brief Constructs a new ParameterEditorController Widget. This widget is used within the PX4VehicleConfig set of screens.
ParameterEditorController::ParameterEditorController(void)
: _currentCategory("Standard") // FIXME: firmware specific
, _parameters(new QmlObjectListModel(this))
: _currentCategory ("Standard") // FIXME: firmware specific
, _parameters (new QmlObjectListModel(this))
, _parameterMgr (_vehicle->parameterManager())
, _componentCategoryPrefix (tr("Component "))
{
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _vehicle->parameterManager()->getCategoryMap();
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _parameterMgr->getDefaultComponentCategoryMap();
_categories = categoryMap.keys();
// Move default category to front
_categories.removeOne(_currentCategory);
_categories.prepend(_currentCategory);
// There is a category for each non default component
for (int compId: _parameterMgr->componentIds()) {
if (compId != _vehicle->defaultComponentId()) {
_categories.append(QString("%1%2").arg(_componentCategoryPrefix).arg(compId));
}
}
// Be careful about no parameters
if (categoryMap.contains(_currentCategory) && categoryMap[_currentCategory].size() != 0) {
_currentGroup = categoryMap[_currentCategory].keys()[0];
@ -54,27 +58,24 @@ ParameterEditorController::~ParameterEditorController() @@ -54,27 +58,24 @@ ParameterEditorController::~ParameterEditorController()
QStringList ParameterEditorController::getGroupsForCategory(const QString& category)
{
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _vehicle->parameterManager()->getCategoryMap();
return categoryMap[category].keys();
}
QStringList ParameterEditorController::getParametersForGroup(const QString& category, const QString& group)
{
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _vehicle->parameterManager()->getCategoryMap();
if (category.startsWith(_componentCategoryPrefix)) {
return QStringList(tr("All"));
} else {
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _parameterMgr->getDefaultComponentCategoryMap();
return categoryMap[category][group];
return categoryMap[category].keys();
}
}
QStringList ParameterEditorController::searchParameters(const QString& searchText, bool searchInName, bool searchInDescriptions)
{
QStringList list;
for(const QString &paramName: _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) {
for(const QString &paramName: _parameterMgr->parameterNames(_vehicle->defaultComponentId())) {
if (searchText.isEmpty()) {
list += paramName;
} else {
Fact* fact = _vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), paramName);
Fact* fact = _parameterMgr->getParameter(_vehicle->defaultComponentId(), paramName);
if (searchInName && fact->name().contains(searchText, Qt::CaseInsensitive)) {
list += paramName;
@ -111,7 +112,7 @@ void ParameterEditorController::saveToFile(const QString& filename) @@ -111,7 +112,7 @@ void ParameterEditorController::saveToFile(const QString& filename)
}
QTextStream stream(&file);
_vehicle->parameterManager()->writeParametersToStream(stream);
_parameterMgr->writeParametersToStream(stream);
file.close();
}
}
@ -129,7 +130,7 @@ void ParameterEditorController::loadFromFile(const QString& filename) @@ -129,7 +130,7 @@ void ParameterEditorController::loadFromFile(const QString& filename)
}
QTextStream stream(&file);
errors = _vehicle->parameterManager()->readParametersFromStream(stream);
errors = _parameterMgr->readParametersFromStream(stream);
file.close();
if (!errors.isEmpty()) {
@ -140,12 +141,12 @@ void ParameterEditorController::loadFromFile(const QString& filename) @@ -140,12 +141,12 @@ void ParameterEditorController::loadFromFile(const QString& filename)
void ParameterEditorController::refresh(void)
{
_vehicle->parameterManager()->refreshAllParameters();
_parameterMgr->refreshAllParameters();
}
void ParameterEditorController::resetAllToDefaults(void)
{
_vehicle->parameterManager()->resetAllParametersToDefaults();
_parameterMgr->resetAllParametersToDefaults();
refresh();
}
@ -167,13 +168,21 @@ void ParameterEditorController::_updateParameters(void) @@ -167,13 +168,21 @@ void ParameterEditorController::_updateParameters(void)
QStringList searchItems = _searchText.split(' ', QString::SkipEmptyParts);
if (searchItems.isEmpty()) {
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _vehicle->parameterManager()->getCategoryMap();
for (const QString& parameter: categoryMap[_currentCategory][_currentGroup]) {
newParameterList.append(_vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), parameter));
if (_currentCategory.startsWith(_componentCategoryPrefix)) {
int compId = _currentCategory.right(_currentCategory.length() - _componentCategoryPrefix.length()).toInt();
for (const QString& paramName: _parameterMgr->parameterNames(compId)) {
newParameterList.append(_parameterMgr->getParameter(compId, paramName));
}
} else {
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _parameterMgr->getDefaultComponentCategoryMap();
for (const QString& parameter: categoryMap[_currentCategory][_currentGroup]) {
newParameterList.append(_parameterMgr->getParameter(_vehicle->defaultComponentId(), parameter));
}
}
} else {
for(const QString &parameter: _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) {
Fact* fact = _vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), parameter);
for(const QString &parameter: _parameterMgr->parameterNames(_vehicle->defaultComponentId())) {
Fact* fact = _parameterMgr->getParameter(_vehicle->defaultComponentId(), parameter);
bool matched = true;
// all of the search items must match in order for the parameter to be added to the list

4
src/QmlControls/ParameterEditorController.h

@ -21,6 +21,7 @@ @@ -21,6 +21,7 @@
#include "UASInterface.h"
#include "FactPanelController.h"
#include "QmlObjectListModel.h"
#include "ParameterManager.h"
class ParameterEditorController : public FactPanelController
{
@ -37,7 +38,6 @@ public: @@ -37,7 +38,6 @@ public:
Q_PROPERTY(QStringList categories MEMBER _categories CONSTANT)
Q_INVOKABLE QStringList getGroupsForCategory(const QString& category);
Q_INVOKABLE QStringList getParametersForGroup(const QString& category, const QString& group);
Q_INVOKABLE QStringList searchParameters(const QString& searchText, bool searchInName=true, bool searchInDescriptions=true);
Q_INVOKABLE void clearRCToParam(void);
@ -64,6 +64,8 @@ private: @@ -64,6 +64,8 @@ private:
QString _currentCategory;
QString _currentGroup;
QmlObjectListModel* _parameters;
ParameterManager* _parameterMgr;
QString _componentCategoryPrefix;
};
#endif

Loading…
Cancel
Save