mirror of https://github.com/ArduPilot/ardupilot
AP_Param: Add parameter to print out all the keys/indexes
For some debugging I was working on I needed to see all the token indexs and group elements.
This commit is contained in:
parent
f6f2e901b8
commit
ab35ac41a5
|
@ -1114,7 +1114,7 @@ void AP_Param::show(const AP_Param *ap, const ParamToken &token,
|
|||
}
|
||||
|
||||
// print the value of all variables
|
||||
void AP_Param::show_all(AP_HAL::BetterStream *port)
|
||||
void AP_Param::show_all(AP_HAL::BetterStream *port, bool showKeyValues)
|
||||
{
|
||||
ParamToken token;
|
||||
AP_Param *ap;
|
||||
|
@ -1123,6 +1123,9 @@ void AP_Param::show_all(AP_HAL::BetterStream *port)
|
|||
for (ap=AP_Param::first(&token, &type);
|
||||
ap;
|
||||
ap=AP_Param::next_scalar(&token, &type)) {
|
||||
if (showKeyValues) {
|
||||
port->printf_P(PSTR("Key %i: Index %i: GroupElement %i : "), token.key, token.idx, token.group_element);
|
||||
}
|
||||
show(ap, token, type, port);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -224,7 +224,7 @@ public:
|
|||
static void erase_all(void);
|
||||
|
||||
/// print the value of all variables
|
||||
static void show_all(AP_HAL::BetterStream *port);
|
||||
static void show_all(AP_HAL::BetterStream *port, bool showKeyValues=false);
|
||||
|
||||
/// print the value of one variable
|
||||
static void show(const AP_Param *param,
|
||||
|
|
Loading…
Reference in New Issue