Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
0ac171d9
Commit
0ac171d9
authored
Nov 08, 2019
by
olliw42
Browse files
move parameter category&group handling for components up to ParameterManager class
parent
142beec4
Changes
4
Hide whitespace changes
Inline
Side-by-side
src/FactSystem/ParameterManager.cc
View file @
0ac171d9
...
...
@@ -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"
},
{
171
,
"Gimbal2"
},
//{ MAV_COMP_ID_GIMBAL2, "Gimbal2" }, //not yet in the used common.h !!
{
172
,
"Gimbal3"
},
//{ MAV_COMP_ID_GIMBAL3, "Gimbal3" },
{
173
,
"Gimbal4"
},
//{ MAV_COMP_ID_GIMBAL4, "Gimbal4" },
{
174
,
"Gimbal5"
},
//{ MAV_COMP_ID_GIMBAL5, "Gimbal5" },
{
175
,
"Gimbal6"
},
//{ 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"
;
...
...
@@ -345,12 +382,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
...
...
@@ -456,15 +492,15 @@ int ParameterManager::_actualComponentId(int componentId)
return
componentId
;
}
void
ParameterManager
::
refreshParameter
(
int
componentId
,
const
QString
&
n
ame
)
void
ParameterManager
::
refreshParameter
(
int
componentId
,
const
QString
&
paramN
ame
)
{
componentId
=
_actualComponentId
(
componentId
);
qCDebug
(
ParameterManagerLog
)
<<
_logVehiclePrefix
(
componentId
)
<<
"refreshParameter - name:"
<<
n
ame
<<
")"
;
qCDebug
(
ParameterManagerLog
)
<<
_logVehiclePrefix
(
componentId
)
<<
"refreshParameter - name:"
<<
paramN
ame
<<
")"
;
_dataMutex
.
lock
();
if
(
_waitingReadParamNameMap
.
contains
(
componentId
))
{
QString
mappedParamName
=
_remapParamNameToVersion
(
n
ame
);
QString
mappedParamName
=
_remapParamNameToVersion
(
paramN
ame
);
_waitingReadParamNameMap
[
componentId
].
remove
(
mappedParamName
);
// Remove old wait entry if there
_waitingReadParamNameMap
[
componentId
][
mappedParamName
]
=
0
;
// Add new wait entry and update retry count
...
...
@@ -476,7 +512,7 @@ void ParameterManager::refreshParameter(int componentId, const QString& name)
_dataMutex
.
unlock
();
_readParameterRaw
(
componentId
,
n
ame
,
-
1
);
_readParameterRaw
(
componentId
,
paramN
ame
,
-
1
);
}
void
ParameterManager
::
refreshParametersPrefix
(
int
componentId
,
const
QString
&
namePrefix
)
...
...
@@ -484,30 +520,30 @@ void ParameterManager::refreshParametersPrefix(int componentId, const QString& n
componentId
=
_actualComponentId
(
componentId
);
qCDebug
(
ParameterManagerLog
)
<<
_logVehiclePrefix
(
componentId
)
<<
"refreshParametersPrefix - name:"
<<
namePrefix
<<
")"
;
for
(
const
QString
&
n
ame
:
_mapParameterName2Variant
[
componentId
].
keys
())
{
if
(
n
ame
.
startsWith
(
namePrefix
))
{
refreshParameter
(
componentId
,
n
ame
);
for
(
const
QString
&
paramN
ame
:
_mapParameterName2Variant
[
componentId
].
keys
())
{
if
(
paramN
ame
.
startsWith
(
namePrefix
))
{
refreshParameter
(
componentId
,
paramN
ame
);
}
}
}
bool
ParameterManager
::
parameterExists
(
int
componentId
,
const
QString
&
n
ame
)
bool
ParameterManager
::
parameterExists
(
int
componentId
,
const
QString
&
paramN
ame
)
{
bool
ret
=
false
;
componentId
=
_actualComponentId
(
componentId
);
if
(
_mapParameterName2Variant
.
contains
(
componentId
))
{
ret
=
_mapParameterName2Variant
[
componentId
].
contains
(
_remapParamNameToVersion
(
n
ame
));
ret
=
_mapParameterName2Variant
[
componentId
].
contains
(
_remapParamNameToVersion
(
paramN
ame
));
}
return
ret
;
}
Fact
*
ParameterManager
::
getParameter
(
int
componentId
,
const
QString
&
n
ame
)
Fact
*
ParameterManager
::
getParameter
(
int
componentId
,
const
QString
&
paramN
ame
)
{
componentId
=
_actualComponentId
(
componentId
);
QString
mappedParamName
=
_remapParamNameToVersion
(
n
ame
);
QString
mappedParamName
=
_remapParamNameToVersion
(
paramN
ame
);
if
(
!
_mapParameterName2Variant
.
contains
(
componentId
)
||
!
_mapParameterName2Variant
[
componentId
].
contains
(
mappedParamName
))
{
qgcApp
()
->
reportMissingParameter
(
componentId
,
mappedParamName
);
return
&
_defaultFact
;
...
...
@@ -527,20 +563,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
][
"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
_mavlinkCompIdHash
.
value
(
componentId
)
+
QString
(
" (compId %1)"
).
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
::
get
Default
Component
CategoryMap
(
void
)
int
ParameterManager
::
getComponent
Id
(
const
QString
&
category
)
{
return
_defaultComponentCategoryMap
;
return
(
_componentCategoryHash
.
contains
(
category
))
?
_componentCategoryHash
.
value
(
category
)
:
_vehicle
->
defaultComponentId
()
;
}
/// Requests missing index based parameters from the vehicle.
...
...
@@ -757,9 +839,9 @@ void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
{
CacheMapName2ParamTypeVal
cacheMap
;
for
(
const
QString
&
n
ame
:
_mapParameterName2Variant
[
componentId
].
keys
())
{
const
Fact
*
fact
=
_mapParameterName2Variant
[
componentId
][
n
ame
].
value
<
Fact
*>
();
cacheMap
[
n
ame
]
=
ParamTypeVal
(
fact
->
type
(),
fact
->
rawValue
());
for
(
const
QString
&
paramN
ame
:
_mapParameterName2Variant
[
componentId
].
keys
())
{
const
Fact
*
fact
=
_mapParameterName2Variant
[
componentId
][
paramN
ame
].
value
<
Fact
*>
();
cacheMap
[
paramN
ame
]
=
ParamTypeVal
(
fact
->
type
(),
fact
->
rawValue
());
}
QFile
cacheFile
(
parameterCacheFile
(
vehicleId
,
componentId
));
...
...
@@ -939,7 +1021,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
"
;
...
...
@@ -1439,7 +1521,7 @@ void ParameterManager::_loadOfflineEditingParams(void)
}
_addMetaDataToDefaultComponent
();
_setupDefaultComponentCategoryMap
();
_setupDefaultComponentCategoryMap
();
//TODO: check if this is really only for the default, or needs to be done for all components !!
_parametersReady
=
true
;
_initialLoadComplete
=
true
;
_debugCacheCRC
.
clear
();
...
...
src/FactSystem/ParameterManager.h
View file @
0ac171d9
...
...
@@ -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
&
n
ame
);
void
refreshParameter
(
int
componentId
,
const
QString
&
paramN
ame
);
/// 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
&
n
ame
);
bool
parameterExists
(
int
componentId
,
const
QString
&
paramN
ame
);
/// 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
&
n
ame
);
Fact
*
getParameter
(
int
componentId
,
const
QString
&
paramN
ame
);
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
...
...
src/QmlControls/ParameterEditorController.cc
View file @
0ac171d9
...
...
@@ -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
->
get
Default
ComponentCategoryMap
();
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
(
_c
omponentCategory
Prefix
).
arg
(
compId
));
_categories
.
append
(
_parameterMgr
->
getC
omponentCategory
(
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
&
parame
ter
:
_parameterMgr
->
parameterNames
(
_vehicle
->
defaultComponentId
()))
{
Fact
*
fact
=
_parameterMgr
->
getParameter
(
_vehicle
->
defaultComponentId
(),
parame
ter
);
for
(
const
QString
&
para
Na
me
:
_parameterMgr
->
parameterNames
(
_vehicle
->
defaultComponentId
()))
{
Fact
*
fact
=
_parameterMgr
->
getParameter
(
_vehicle
->
defaultComponentId
(),
para
Na
me
);
bool
matched
=
_shouldShow
(
fact
);
// All of the search items must match in order for the parameter to be added to the list
if
(
matched
)
{
...
...
src/QmlControls/ParameterEditorController.h
View file @
0ac171d9
...
...
@@ -71,7 +71,6 @@ private:
QString
_currentGroup
;
QmlObjectListModel
*
_parameters
;
ParameterManager
*
_parameterMgr
;
QString
_componentCategoryPrefix
;
bool
_showModifiedOnly
;
};
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment