Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
b51f2735
Unverified
Commit
b51f2735
authored
Nov 07, 2018
by
Don Gagne
Committed by
GitHub
Nov 07, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6993 from DonLakeFlyer/CompParam
Parameter Editor: Support editing of non-default component params
parents
4a6e42d3
5332ca14
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
73 additions
and
52 deletions
+73
-52
ParameterManager.cc
src/FactSystem/ParameterManager.cc
+12
-7
ParameterManager.h
src/FactSystem/ParameterManager.h
+5
-3
ParameterEditorController.cc
src/QmlControls/ParameterEditorController.cc
+37
-28
ParameterEditorController.h
src/QmlControls/ParameterEditorController.h
+3
-1
MockLink.cc
src/comm/MockLink.cc
+13
-11
MockLink.h
src/comm/MockLink.h
+2
-2
PX4MockLink.params
src/comm/PX4MockLink.params
+1
-0
No files found.
src/FactSystem/ParameterManager.cc
View file @
b51f2735
...
...
@@ -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
// new params. By handling this here, we can pick up components which finish up later than the default
// component param set.
_setupCategoryMap
();
_setup
DefaultComponent
CategoryMap
();
}
}
...
...
@@ -529,20 +529,20 @@ QStringList ParameterManager::parameterNames(int componentId)
return
names
;
}
void
ParameterManager
::
_setupCategoryMap
(
void
)
void
ParameterManager
::
_setup
DefaultComponent
CategoryMap
(
void
)
{
// Must be able to handle being called multiple times
_
c
ategoryMap
.
clear
();
_
defaultComponentC
ategoryMap
.
clear
();
for
(
const
QString
&
name
:
_mapParameterName2Variant
[
_vehicle
->
defaultComponentId
()].
keys
())
{
Fact
*
fact
=
_mapParameterName2Variant
[
_vehicle
->
defaultComponentId
()][
name
].
value
<
Fact
*>
();
_
c
ategoryMap
[
fact
->
category
()][
fact
->
group
()]
+=
name
;
_
defaultComponentC
ategoryMap
[
fact
->
category
()][
fact
->
group
()]
+=
name
;
}
}
const
QMap
<
QString
,
QMap
<
QString
,
QStringList
>
>&
ParameterManager
::
getCategoryMap
(
void
)
const
QMap
<
QString
,
QMap
<
QString
,
QStringList
>
>&
ParameterManager
::
get
DefaultComponent
CategoryMap
(
void
)
{
return
_
c
ategoryMap
;
return
_
defaultComponentC
ategoryMap
;
}
/// Requests missing index based parameters from the vehicle.
...
...
@@ -1433,7 +1433,7 @@ void ParameterManager::_loadOfflineEditingParams(void)
}
_addMetaDataToDefaultComponent
();
_setupCategoryMap
();
_setup
DefaultComponent
CategoryMap
();
_parametersReady
=
true
;
_initialLoadComplete
=
true
;
_debugCacheCRC
.
clear
();
...
...
@@ -1567,3 +1567,8 @@ void ParameterManager::_setLoadProgress(double loadProgress)
_loadProgress
=
loadProgress
;
emit
loadProgressChanged
(
loadProgress
);
}
QList
<
int
>
ParameterManager
::
componentIds
(
void
)
{
return
_paramCountMap
.
keys
();
}
src/FactSystem/ParameterManager.h
View file @
b51f2735
...
...
@@ -49,6 +49,8 @@ public:
/// @return Location of parameter cache file
static
QString
parameterCacheFile
(
int
vehicleId
,
int
componentId
);
QList
<
int
>
componentIds
(
void
);
/// Re-request the full set of parameters from the autopilot
void
refreshAllParameters
(
uint8_t
componentID
=
MAV_COMP_ID_ALL
);
...
...
@@ -75,7 +77,7 @@ public:
/// @param name Parameter name
Fact
*
getParameter
(
int
componentId
,
const
QString
&
name
);
const
QMap
<
QString
,
QMap
<
QString
,
QStringList
>
>&
getCategoryMap
(
void
);
const
QMap
<
QString
,
QMap
<
QString
,
QStringList
>
>&
get
DefaultComponent
CategoryMap
(
void
);
/// Returns error messages from loading
QString
readParametersFromStream
(
QTextStream
&
stream
);
...
...
@@ -128,7 +130,7 @@ protected:
private:
static
QVariant
_stringToTypedVariant
(
const
QString
&
string
,
FactMetaData
::
ValueType_t
type
,
bool
failOk
=
false
);
int
_actualComponentId
(
int
componentId
);
void
_setupCategoryMap
(
void
);
void
_setup
DefaultComponent
CategoryMap
(
void
);
void
_readParameterRaw
(
int
componentId
,
const
QString
&
paramName
,
int
paramIndex
);
void
_writeParameterRaw
(
int
componentId
,
const
QString
&
paramName
,
const
QVariant
&
value
);
void
_writeLocalParamCache
(
int
vehicleId
,
int
componentId
);
...
...
@@ -151,7 +153,7 @@ private:
QMap
<
int
,
QVariantMap
>
_mapParameterName2Variant
;
// Category map of default component parameters
QMap
<
QString
/* category */
,
QMap
<
QString
/* group */
,
QStringList
/* parameter names */
>
>
_
c
ategoryMap
;
QMap
<
QString
/* category */
,
QMap
<
QString
/* group */
,
QStringList
/* parameter names */
>
>
_
defaultComponentC
ategoryMap
;
double
_loadProgress
;
///< Parameter load progess, [0.0,1.0]
bool
_parametersReady
;
///< true: parameter load complete
...
...
src/QmlControls/ParameterEditorController.cc
View file @
b51f2735
...
...
@@ -7,10 +7,6 @@
*
****************************************************************************/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "ParameterEditorController.h"
#include "QGCApplication.h"
#include "ParameterManager.h"
...
...
@@ -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
()
->
ge
tCategoryMap
();
const
QMap
<
QString
,
QMap
<
QString
,
QStringList
>
>&
categoryMap
=
_
parameterMgr
->
getDefaultComponen
tCategoryMap
();
_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()
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)
}
QTextStream
stream
(
&
file
);
_
vehicle
->
parameterManager
()
->
writeParametersToStream
(
stream
);
_
parameterMgr
->
writeParametersToStream
(
stream
);
file
.
close
();
}
}
...
...
@@ -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)
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)
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
...
...
src/QmlControls/ParameterEditorController.h
View file @
b51f2735
...
...
@@ -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:
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:
QString
_currentCategory
;
QString
_currentGroup
;
QmlObjectListModel
*
_parameters
;
ParameterManager
*
_parameterMgr
;
QString
_componentCategoryPrefix
;
};
#endif
src/comm/MockLink.cc
View file @
b51f2735
...
...
@@ -257,6 +257,7 @@ void MockLink::_loadParams(void)
QStringList
paramData
=
line
.
split
(
"
\t
"
);
Q_ASSERT
(
paramData
.
count
()
==
5
);
int
compId
=
paramData
.
at
(
1
).
toInt
();
QString
paramName
=
paramData
.
at
(
2
);
QString
valStr
=
paramData
.
at
(
3
);
uint
paramType
=
paramData
.
at
(
4
).
toUInt
();
...
...
@@ -292,8 +293,8 @@ void MockLink::_loadParams(void)
qCDebug
(
MockLinkVerboseLog
)
<<
"Loading param"
<<
paramName
<<
paramValue
;
_mapParamName2Value
[
_vehicleComponent
Id
][
paramName
]
=
paramValue
;
_mapParamName2MavParamType
[
paramName
]
=
static_cast
<
MAV_PARAM_TYPE
>
(
paramType
);
_mapParamName2Value
[
comp
Id
][
paramName
]
=
paramValue
;
_mapParamName2MavParamType
[
compId
][
paramName
]
=
static_cast
<
MAV_PARAM_TYPE
>
(
paramType
);
}
}
...
...
@@ -515,11 +516,11 @@ void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramN
Q_ASSERT
(
_mapParamName2Value
.
contains
(
componentId
));
Q_ASSERT
(
_mapParamName2Value
[
componentId
].
contains
(
paramName
));
Q_ASSERT
(
_mapParamName2MavParamType
.
contains
(
paramName
));
Q_ASSERT
(
_mapParamName2MavParamType
[
componentId
]
.
contains
(
paramName
));
valueUnion
.
param_float
=
paramFloat
;
MAV_PARAM_TYPE
paramType
=
_mapParamName2MavParamType
[
paramName
];
MAV_PARAM_TYPE
paramType
=
_mapParamName2MavParamType
[
componentId
][
paramName
];
QVariant
paramVariant
;
...
...
@@ -569,9 +570,9 @@ float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
Q_ASSERT
(
_mapParamName2Value
.
contains
(
componentId
));
Q_ASSERT
(
_mapParamName2Value
[
componentId
].
contains
(
paramName
));
Q_ASSERT
(
_mapParamName2MavParamType
.
contains
(
paramName
));
Q_ASSERT
(
_mapParamName2MavParamType
[
componentId
]
.
contains
(
paramName
));
MAV_PARAM_TYPE
paramType
=
_mapParamName2MavParamType
[
paramName
];
MAV_PARAM_TYPE
paramType
=
_mapParamName2MavParamType
[
componentId
][
paramName
];
QVariant
paramVar
=
_mapParamName2Value
[
componentId
][
paramName
];
switch
(
paramType
)
{
...
...
@@ -677,9 +678,9 @@ void MockLink::_paramRequestListWorker(void)
mavlink_message_t
responseMsg
;
Q_ASSERT
(
_mapParamName2Value
[
componentId
].
contains
(
paramName
));
Q_ASSERT
(
_mapParamName2MavParamType
.
contains
(
paramName
));
Q_ASSERT
(
_mapParamName2MavParamType
[
componentId
]
.
contains
(
paramName
));
MAV_PARAM_TYPE
paramType
=
_mapParamName2MavParamType
[
paramName
];
MAV_PARAM_TYPE
paramType
=
_mapParamName2MavParamType
[
componentId
][
paramName
];
Q_ASSERT
(
paramName
.
length
()
<=
MAVLINK_MSG_ID_PARAM_VALUE_LEN
);
strncpy
(
paramId
,
paramName
.
toLocal8Bit
().
constData
(),
MAVLINK_MSG_ID_PARAM_VALUE_LEN
);
...
...
@@ -726,8 +727,9 @@ void MockLink::_handleParamSet(const mavlink_message_t& msg)
qCDebug
(
MockLinkLog
)
<<
"_handleParamSet"
<<
componentId
<<
paramId
<<
request
.
param_type
;
Q_ASSERT
(
_mapParamName2Value
.
contains
(
componentId
));
Q_ASSERT
(
_mapParamName2MavParamType
.
contains
(
componentId
));
Q_ASSERT
(
_mapParamName2Value
[
componentId
].
contains
(
paramId
));
Q_ASSERT
(
request
.
param_type
==
_mapParamName2MavParamType
[
paramId
]);
Q_ASSERT
(
request
.
param_type
==
_mapParamName2MavParamType
[
componentId
][
paramId
]);
// Save the new value
_setParamFloatUnionIntoMap
(
componentId
,
paramId
,
request
.
param_value
);
...
...
@@ -795,7 +797,7 @@ void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
}
Q_ASSERT
(
_mapParamName2Value
[
componentId
].
contains
(
paramId
));
Q_ASSERT
(
_mapParamName2MavParamType
.
contains
(
paramId
));
Q_ASSERT
(
_mapParamName2MavParamType
[
componentId
]
.
contains
(
paramId
));
if
(
_failureMode
==
MockConfiguration
::
FailMissingParamOnAllRequests
&&
strcmp
(
paramId
,
_failParam
)
==
0
)
{
qCDebug
(
MockLinkLog
)
<<
"Ignoring request read for "
<<
_failParam
;
...
...
@@ -809,7 +811,7 @@ void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
&
responseMsg
,
// Outgoing message
paramId
,
// Parameter name
_floatUnionForParam
(
componentId
,
paramId
),
// Parameter value
_mapParamName2MavParamType
[
paramId
],
// Parameter type
_mapParamName2MavParamType
[
componentId
][
paramId
],
// Parameter type
_mapParamName2Value
[
componentId
].
count
(),
// Total number of parameters
_mapParamName2Value
[
componentId
].
keys
().
indexOf
(
paramId
));
// Index of this parameter
respondWithMavlinkMessage
(
responseMsg
);
...
...
src/comm/MockLink.h
View file @
b51f2735
...
...
@@ -216,8 +216,8 @@ private:
bool
_inNSH
;
bool
_mavlinkStarted
;
QMap
<
int
,
QMap
<
QString
,
QVariant
>
>
_mapParamName2Value
;
QMap
<
QString
,
MAV_PARAM_TYPE
>
_mapParamName2MavParamType
;
QMap
<
int
,
QMap
<
QString
,
QVariant
>
>
_mapParamName2Value
;
QMap
<
int
,
QMap
<
QString
,
MAV_PARAM_TYPE
>>
_mapParamName2MavParamType
;
uint8_t
_mavBaseMode
;
uint32_t
_mavCustomMode
;
...
...
src/comm/PX4MockLink.params
View file @
b51f2735
...
...
@@ -737,3 +737,4 @@
1 1 TRIG_MODE 4 6
1 1 VT_B_DEC_MSS 2.000000000000000000 9
1 1 VT_B_REV_DEL 0.000000000000000000 9
1 2 VT_B_REV_DEL 0.000000000000000000 9
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a 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