Unverified Commit 047eb534 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7985 from olliw42/pr-compid-2nd

ParameterManager, ParameterEditorController: Nice category & groups for components
parents 23b5156f 55c1c67d
......@@ -26,6 +26,43 @@ QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "ParameterManagerVer
QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "ParameterManagerVerbose2Log")
QGC_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog, "ParameterManagerDebugCacheFailureLog") // Turn on to debug parameter cache crc misses
const QHash<int, QString> _mavlinkCompIdHash {
{ MAV_COMP_ID_CAMERA, "Camera1" },
{ MAV_COMP_ID_CAMERA2, "Camera2" },
{ MAV_COMP_ID_CAMERA3, "Camera3" },
{ MAV_COMP_ID_CAMERA4, "Camera4" },
{ MAV_COMP_ID_CAMERA5, "Camera5" },
{ MAV_COMP_ID_CAMERA6, "Camera6" },
{ MAV_COMP_ID_SERVO1, "Servo1" },
{ MAV_COMP_ID_SERVO2, "Servo2" },
{ MAV_COMP_ID_SERVO3, "Servo3" },
{ MAV_COMP_ID_SERVO4, "Servo4" },
{ MAV_COMP_ID_SERVO5, "Servo5" },
{ MAV_COMP_ID_SERVO6, "Servo6" },
{ MAV_COMP_ID_SERVO7, "Servo7" },
{ MAV_COMP_ID_SERVO8, "Servo8" },
{ MAV_COMP_ID_SERVO9, "Servo9" },
{ MAV_COMP_ID_SERVO10, "Servo10" },
{ MAV_COMP_ID_SERVO11, "Servo11" },
{ MAV_COMP_ID_SERVO12, "Servo12" },
{ MAV_COMP_ID_SERVO13, "Servo13" },
{ MAV_COMP_ID_SERVO14, "Servo14" },
{ MAV_COMP_ID_GIMBAL, "Gimbal1" },
{ MAV_COMP_ID_ADSB, "ADSB" },
{ MAV_COMP_ID_OSD, "OSD" },
{ MAV_COMP_ID_FLARM, "FLARM" },
{ MAV_COMP_ID_GIMBAL2, "Gimbal2" },
{ MAV_COMP_ID_GIMBAL3, "Gimbal3" },
{ MAV_COMP_ID_GIMBAL4, "Gimbal4" },
{ MAV_COMP_ID_GIMBAL5, "Gimbal5" },
{ MAV_COMP_ID_GIMBAL6, "Gimbal6" },
{ MAV_COMP_ID_IMU, "IMU1" },
{ MAV_COMP_ID_IMU_2, "IMU2" },
{ MAV_COMP_ID_IMU_3, "IMU3" },
{ MAV_COMP_ID_GPS, "GPS1" },
{ MAV_COMP_ID_GPS2, "GPS2" }
};
const char* ParameterManager::_cachedMetaDataFilePrefix = "ParameterFactMetaData";
const char* ParameterManager::_jsonParametersKey = "parameters";
const char* ParameterManager::_jsonCompIdKey = "compId";
......@@ -393,12 +430,11 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
// Add meta data to default component. We need to do this before we setup the group map since group
// map requires meta data.
_addMetaDataToDefaultComponent();
// 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
// component param set.
_setupDefaultComponentCategoryMap();
}
// 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
// component param set.
_setupComponentCategoryMap(componentId);
}
// Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
......@@ -509,15 +545,15 @@ int ParameterManager::_actualComponentId(int componentId)
return componentId;
}
void ParameterManager::refreshParameter(int componentId, const QString& name)
void ParameterManager::refreshParameter(int componentId, const QString& paramName)
{
componentId = _actualComponentId(componentId);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << name << ")";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << paramName << ")";
_dataMutex.lock();
if (_waitingReadParamNameMap.contains(componentId)) {
QString mappedParamName = _remapParamNameToVersion(name);
QString mappedParamName = _remapParamNameToVersion(paramName);
if (_waitingReadParamNameMap[componentId].contains(mappedParamName)) {
_waitingReadParamNameMap[componentId].remove(mappedParamName);
......@@ -534,7 +570,7 @@ void ParameterManager::refreshParameter(int componentId, const QString& name)
_dataMutex.unlock();
_readParameterRaw(componentId, name, -1);
_readParameterRaw(componentId, paramName, -1);
}
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
......@@ -542,30 +578,30 @@ void ParameterManager::refreshParametersPrefix(int componentId, const QString& n
componentId = _actualComponentId(componentId);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
for(const QString &name: _mapParameterName2Variant[componentId].keys()) {
if (name.startsWith(namePrefix)) {
refreshParameter(componentId, name);
for(const QString &paramName: _mapParameterName2Variant[componentId].keys()) {
if (paramName.startsWith(namePrefix)) {
refreshParameter(componentId, paramName);
}
}
}
bool ParameterManager::parameterExists(int componentId, const QString& name)
bool ParameterManager::parameterExists(int componentId, const QString& paramName)
{
bool ret = false;
componentId = _actualComponentId(componentId);
if (_mapParameterName2Variant.contains(componentId)) {
ret = _mapParameterName2Variant[componentId].contains(_remapParamNameToVersion(name));
ret = _mapParameterName2Variant[componentId].contains(_remapParamNameToVersion(paramName));
}
return ret;
}
Fact* ParameterManager::getParameter(int componentId, const QString& name)
Fact* ParameterManager::getParameter(int componentId, const QString& paramName)
{
componentId = _actualComponentId(componentId);
QString mappedParamName = _remapParamNameToVersion(name);
QString mappedParamName = _remapParamNameToVersion(paramName);
if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(mappedParamName)) {
qgcApp()->reportMissingParameter(componentId, mappedParamName);
return &_defaultFact;
......@@ -585,20 +621,66 @@ QStringList ParameterManager::parameterNames(int componentId)
return names;
}
void ParameterManager::_setupComponentCategoryMap(int componentId)
{
if (componentId == _vehicle->defaultComponentId()) {
_setupDefaultComponentCategoryMap();
return;
}
ComponentCategoryMapType& componentCategoryMap = _componentCategoryMaps[componentId];
QString category = getComponentCategory(componentId);
// Must be able to handle being called multiple times
componentCategoryMap.clear();
// Fill parameters into the group determined by param name
for (const QString &paramName: _mapParameterName2Variant[componentId].keys()) {
int i = paramName.indexOf("_");
if (i > 0) {
componentCategoryMap[category][paramName.left(i)] += paramName;
} else {
componentCategoryMap[category][tr("Misc")] += paramName;
}
}
// Memorize category for component ID
if (!_componentCategoryHash.contains(category)) {
_componentCategoryHash.insert(category, componentId);
}
}
void ParameterManager::_setupDefaultComponentCategoryMap(void)
{
ComponentCategoryMapType& defaultComponentCategoryMap = _componentCategoryMaps[_vehicle->defaultComponentId()];
// Must be able to handle being called multiple times
_defaultComponentCategoryMap.clear();
defaultComponentCategoryMap.clear();
for (const QString &paramName: _mapParameterName2Variant[_vehicle->defaultComponentId()].keys()) {
Fact* fact = _mapParameterName2Variant[_vehicle->defaultComponentId()][paramName].value<Fact*>();
defaultComponentCategoryMap[fact->category()][fact->group()] += paramName;
}
}
for (const QString &name: _mapParameterName2Variant[_vehicle->defaultComponentId()].keys()) {
Fact* fact = _mapParameterName2Variant[_vehicle->defaultComponentId()][name].value<Fact*>();
_defaultComponentCategoryMap[fact->category()][fact->group()] += name;
QString ParameterManager::getComponentCategory(int componentId)
{
if (_mavlinkCompIdHash.contains(componentId)) {
return tr("Component %1 (%2)").arg(_mavlinkCompIdHash.value(componentId)).arg(componentId);
}
QString componentCategoryPrefix = tr("Component ");
return QString("%1%2").arg(componentCategoryPrefix).arg(componentId);
}
const QMap<QString, QMap<QString, QStringList> >& ParameterManager::getComponentCategoryMap(int componentId)
{
return _componentCategoryMaps[componentId];
}
const QMap<QString, QMap<QString, QStringList> >& ParameterManager::getDefaultComponentCategoryMap(void)
int ParameterManager::getComponentId(const QString& category)
{
return _defaultComponentCategoryMap;
return (_componentCategoryHash.contains(category)) ? _componentCategoryHash.value(category) : _vehicle->defaultComponentId();
}
/// Requests missing index based parameters from the vehicle.
......@@ -815,9 +897,9 @@ void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
{
CacheMapName2ParamTypeVal cacheMap;
for(const QString& name: _mapParameterName2Variant[componentId].keys()) {
const Fact *fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
cacheMap[name] = ParamTypeVal(fact->type(), fact->rawValue());
for(const QString& paramName: _mapParameterName2Variant[componentId].keys()) {
const Fact *fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
cacheMap[paramName] = ParamTypeVal(fact->type(), fact->rawValue());
}
QFile cacheFile(parameterCacheFile(vehicleId, componentId));
......@@ -1008,7 +1090,7 @@ QString ParameterManager::readParametersFromStream(QTextStream& stream)
return errors;
}
void ParameterManager::writeParametersToStream(QTextStream &stream)
void ParameterManager::writeParametersToStream(QTextStream& stream)
{
stream << "# Onboard parameters for Vehicle " << _vehicle->id() << "\n";
stream << "#\n";
......
......@@ -57,7 +57,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);
......@@ -68,7 +68,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);
......@@ -77,14 +77,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; }
......@@ -137,6 +139,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);
......@@ -160,8 +163,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