Commit 0e6902e3 authored by Don Gagne's avatar Don Gagne

parent b974f350
...@@ -351,7 +351,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString ...@@ -351,7 +351,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
// When we are getting the very last component param index, reset the group maps to update for the // When we are getting the very last component param index, reset the group maps to update for the
// new params. By handling this here, we can pick up components which finish up later than the default // new params. By handling this here, we can pick up components which finish up later than the default
// component param set. // component param set.
_setupCategoryMap(); _setupDefaultComponentCategoryMap();
} }
} }
...@@ -529,20 +529,20 @@ QStringList ParameterManager::parameterNames(int componentId) ...@@ -529,20 +529,20 @@ QStringList ParameterManager::parameterNames(int componentId)
return names; return names;
} }
void ParameterManager::_setupCategoryMap(void) void ParameterManager::_setupDefaultComponentCategoryMap(void)
{ {
// Must be able to handle being called multiple times // Must be able to handle being called multiple times
_categoryMap.clear(); _defaultComponentCategoryMap.clear();
for (const QString &name: _mapParameterName2Variant[_vehicle->defaultComponentId()].keys()) { for (const QString &name: _mapParameterName2Variant[_vehicle->defaultComponentId()].keys()) {
Fact* fact = _mapParameterName2Variant[_vehicle->defaultComponentId()][name].value<Fact*>(); Fact* fact = _mapParameterName2Variant[_vehicle->defaultComponentId()][name].value<Fact*>();
_categoryMap[fact->category()][fact->group()] += name; _defaultComponentCategoryMap[fact->category()][fact->group()] += name;
} }
} }
const QMap<QString, QMap<QString, QStringList> >& ParameterManager::getCategoryMap(void) const QMap<QString, QMap<QString, QStringList> >& ParameterManager::getDefaultComponentCategoryMap(void)
{ {
return _categoryMap; return _defaultComponentCategoryMap;
} }
/// Requests missing index based parameters from the vehicle. /// Requests missing index based parameters from the vehicle.
...@@ -1433,7 +1433,7 @@ void ParameterManager::_loadOfflineEditingParams(void) ...@@ -1433,7 +1433,7 @@ void ParameterManager::_loadOfflineEditingParams(void)
} }
_addMetaDataToDefaultComponent(); _addMetaDataToDefaultComponent();
_setupCategoryMap(); _setupDefaultComponentCategoryMap();
_parametersReady = true; _parametersReady = true;
_initialLoadComplete = true; _initialLoadComplete = true;
_debugCacheCRC.clear(); _debugCacheCRC.clear();
...@@ -1567,3 +1567,8 @@ void ParameterManager::_setLoadProgress(double loadProgress) ...@@ -1567,3 +1567,8 @@ void ParameterManager::_setLoadProgress(double loadProgress)
_loadProgress = loadProgress; _loadProgress = loadProgress;
emit loadProgressChanged(loadProgress); emit loadProgressChanged(loadProgress);
} }
QList<int> ParameterManager::componentIds(void)
{
return _paramCountMap.keys();
}
...@@ -49,6 +49,8 @@ public: ...@@ -49,6 +49,8 @@ public:
/// @return Location of parameter cache file /// @return Location of parameter cache file
static QString parameterCacheFile(int vehicleId, int componentId); static QString parameterCacheFile(int vehicleId, int componentId);
QList<int> componentIds(void);
/// Re-request the full set of parameters from the autopilot /// Re-request the full set of parameters from the autopilot
void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL); void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL);
...@@ -75,7 +77,7 @@ public: ...@@ -75,7 +77,7 @@ public:
/// @param name Parameter name /// @param name Parameter name
Fact* getParameter(int componentId, const QString& name); Fact* getParameter(int componentId, const QString& name);
const QMap<QString, QMap<QString, QStringList> >& getCategoryMap(void); const QMap<QString, QMap<QString, QStringList> >& getDefaultComponentCategoryMap(void);
/// Returns error messages from loading /// Returns error messages from loading
QString readParametersFromStream(QTextStream& stream); QString readParametersFromStream(QTextStream& stream);
...@@ -128,7 +130,7 @@ protected: ...@@ -128,7 +130,7 @@ protected:
private: private:
static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false); static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
int _actualComponentId(int componentId); int _actualComponentId(int componentId);
void _setupCategoryMap(void); void _setupDefaultComponentCategoryMap(void);
void _readParameterRaw(int componentId, const QString& paramName, int paramIndex); void _readParameterRaw(int componentId, const QString& paramName, int paramIndex);
void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value); void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
void _writeLocalParamCache(int vehicleId, int componentId); void _writeLocalParamCache(int vehicleId, int componentId);
...@@ -151,7 +153,7 @@ private: ...@@ -151,7 +153,7 @@ private:
QMap<int, QVariantMap> _mapParameterName2Variant; QMap<int, QVariantMap> _mapParameterName2Variant;
// Category map of default component parameters // Category map of default component parameters
QMap<QString /* category */, QMap<QString /* group */, QStringList /* parameter names */> > _categoryMap; QMap<QString /* category */, QMap<QString /* group */, QStringList /* parameter names */> > _defaultComponentCategoryMap;
double _loadProgress; ///< Parameter load progess, [0.0,1.0] double _loadProgress; ///< Parameter load progess, [0.0,1.0]
bool _parametersReady; ///< true: parameter load complete bool _parametersReady; ///< true: parameter load complete
......
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