mirror of https://github.com/ArduPilot/ardupilot
AP_Param: added find_top_level_key_by_pointer
This commit is contained in:
parent
eddb0a7376
commit
36caf3da49
|
@ -962,6 +962,23 @@ bool AP_Param::find_key_by_pointer(const void *ptr, uint16_t &key)
|
|||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
Find key to top level group parameters by pointer
|
||||
*/
|
||||
bool AP_Param::find_top_level_key_by_pointer(const void *ptr, uint16_t &key)
|
||||
{
|
||||
for (uint16_t i=0; i<_num_vars; i++) {
|
||||
if (_var_info[i].type != AP_PARAM_GROUP) {
|
||||
continue;
|
||||
}
|
||||
if (ptr == (void **)_var_info[i].ptr) {
|
||||
key = _var_info[i].key;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
// Find a object by name.
|
||||
//
|
||||
|
|
|
@ -303,6 +303,14 @@ public:
|
|||
ptrdiff_t offset, uint16_t &key);
|
||||
static bool find_key_by_pointer(const void *ptr, uint16_t &key);
|
||||
|
||||
/// Find key of top level group variable by pointer
|
||||
///
|
||||
///
|
||||
/// @param p Pointer to variable
|
||||
/// @return key for variable
|
||||
static bool find_top_level_key_by_pointer(const void *ptr, uint16_t &key);
|
||||
|
||||
|
||||
/// Find a object in the top level var_info table
|
||||
///
|
||||
/// If the variable has no name, it cannot be found by this interface.
|
||||
|
|
Loading…
Reference in New Issue