Commit 0ac171d9 authored by olliw42's avatar olliw42

move parameter category&group handling for components up to ParameterManager class

parent 142beec4
This diff is collapsed.
......@@ -56,7 +56,7 @@ public:
void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL);
/// Request a refresh on the specific parameter
void refreshParameter(int componentId, const QString& name);
void refreshParameter(int componentId, const QString& paramName);
/// Request a refresh on all parameters that begin with the specified prefix
void refreshParametersPrefix(int componentId, const QString& namePrefix);
......@@ -67,7 +67,7 @@ public:
/// Returns true if the specifed parameter exists
/// @param componentId Component id or FactSystem::defaultComponentId
/// @param name Parameter name
bool parameterExists(int componentId, const QString& name);
bool parameterExists(int componentId, const QString& paramName);
/// Returns all parameter names
QStringList parameterNames(int componentId);
......@@ -76,14 +76,16 @@ public:
/// a missing parameter error to user if parameter does not exist.
/// @param componentId Component id or FactSystem::defaultComponentId
/// @param name Parameter name
Fact* getParameter(int componentId, const QString& name);
Fact* getParameter(int componentId, const QString& paramName);
const QMap<QString, QMap<QString, QStringList> >& getDefaultComponentCategoryMap(void);
int getComponentId(const QString& category);
QString getComponentCategory(int componentId);
const QMap<QString, QMap<QString, QStringList> >& getComponentCategoryMap(int componentId);
/// Returns error messages from loading
QString readParametersFromStream(QTextStream& stream);
void writeParametersToStream(QTextStream &stream);
void writeParametersToStream(QTextStream& stream);
/// Returns the version number for the parameter set, -1 if not known
int parameterSetVersion(void) { return _parameterSetMajorVersion; }
......@@ -133,6 +135,7 @@ private:
static FirmwarePlugin* _anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT firmwareType);
int _actualComponentId(int componentId);
void _setupComponentCategoryMap(int componentId);
void _setupDefaultComponentCategoryMap(void);
void _readParameterRaw(int componentId, const QString& paramName, int paramIndex);
void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
......@@ -155,8 +158,10 @@ private:
/// Second mapping is parameter name, to Fact* in QVariant
QMap<int, QVariantMap> _mapParameterName2Variant;
// Category map of default component parameters
QMap<QString /* category */, QMap<QString /* group */, QStringList /* parameter names */> > _defaultComponentCategoryMap;
// List of category map of component parameters
typedef QMap<QString, QMap<QString, QStringList>> ComponentCategoryMapType; //<Key: category, Value: Map< Key: group, Value: parameter names list >>
QMap<int, ComponentCategoryMapType> _componentCategoryMaps;
QHash<QString, int> _componentCategoryHash;
double _loadProgress; ///< Parameter load progess, [0.0,1.0]
bool _parametersReady; ///< true: parameter load complete
......
......@@ -23,10 +23,9 @@ ParameterEditorController::ParameterEditorController(void)
: _currentCategory ("Standard") // FIXME: firmware specific
, _parameters (new QmlObjectListModel(this))
, _parameterMgr (_vehicle->parameterManager())
, _componentCategoryPrefix (tr("Component "))
, _showModifiedOnly (false)
{
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _parameterMgr->getDefaultComponentCategoryMap();
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _parameterMgr->getComponentCategoryMap(_vehicle->defaultComponentId());
_categories = categoryMap.keys();
// Move default category to front
......@@ -36,7 +35,7 @@ ParameterEditorController::ParameterEditorController(void)
// 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));
_categories.append(_parameterMgr->getComponentCategory(compId));
}
}
......@@ -44,6 +43,7 @@ ParameterEditorController::ParameterEditorController(void)
if (categoryMap.contains(_currentCategory) && categoryMap[_currentCategory].size() != 0) {
_currentGroup = categoryMap[_currentCategory].keys()[0];
}
_updateParameters();
connect(this, &ParameterEditorController::searchTextChanged, this, &ParameterEditorController::_updateParameters);
......@@ -59,13 +59,9 @@ ParameterEditorController::~ParameterEditorController()
QStringList ParameterEditorController::getGroupsForCategory(const QString& category)
{
if (category.startsWith(_componentCategoryPrefix)) {
return QStringList(tr("All"));
} else {
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _parameterMgr->getDefaultComponentCategoryMap();
return categoryMap[category].keys();
}
int compId = _parameterMgr->getComponentId(category);
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _parameterMgr->getComponentCategoryMap(compId);
return categoryMap[category].keys();
}
QStringList ParameterEditorController::searchParameters(const QString& searchText, bool searchInName, bool searchInDescriptions)
......@@ -182,21 +178,14 @@ void ParameterEditorController::_updateParameters(void)
QStringList searchItems = _searchText.split(' ', QString::SkipEmptyParts);
if (searchItems.isEmpty() && !_showModifiedOnly) {
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));
}
int compId = _parameterMgr->getComponentId(_currentCategory);
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _parameterMgr->getComponentCategoryMap(compId);
for (const QString& paramName: categoryMap[_currentCategory][_currentGroup]) {
newParameterList.append(_parameterMgr->getParameter(compId, paramName));
}
} else {
for(const QString &parameter: _parameterMgr->parameterNames(_vehicle->defaultComponentId())) {
Fact* fact = _parameterMgr->getParameter(_vehicle->defaultComponentId(), parameter);
for(const QString &paraName: _parameterMgr->parameterNames(_vehicle->defaultComponentId())) {
Fact* fact = _parameterMgr->getParameter(_vehicle->defaultComponentId(), paraName);
bool matched = _shouldShow(fact);
// All of the search items must match in order for the parameter to be added to the list
if(matched) {
......
......@@ -71,7 +71,6 @@ private:
QString _currentGroup;
QmlObjectListModel* _parameters;
ParameterManager* _parameterMgr;
QString _componentCategoryPrefix;
bool _showModifiedOnly;
};
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment