Browse Source

AP_Param: added get_param_by_index

useful for parameter conversion within an object
c415-sdk
Andrew Tridgell 4 years ago
parent
commit
7b98ab0f12
  1. 15
      libraries/AP_Param/AP_Param.cpp
  2. 7
      libraries/AP_Param/AP_Param.h

15
libraries/AP_Param/AP_Param.cpp

@ -1034,6 +1034,21 @@ bool AP_Param::find_top_level_key_by_pointer(const void *ptr, uint16_t &key) @@ -1034,6 +1034,21 @@ bool AP_Param::find_top_level_key_by_pointer(const void *ptr, uint16_t &key)
return false;
}
/*
fetch a parameter value based on the index within a group. This
is used to find the old value of a parameter that has been
removed from an object.
*/
bool AP_Param::get_param_by_index(void *obj_ptr, uint8_t idx, ap_var_type old_ptype, void *pvalue)
{
uint16_t key;
if (!find_top_level_key_by_pointer(obj_ptr, key)) {
return false;
}
const ConversionInfo type_info = {key, idx, old_ptype, nullptr };
return AP_Param::find_old_parameter(&type_info, (AP_Param *)pvalue);
}
// Find a object by name.
//

7
libraries/AP_Param/AP_Param.h

@ -440,6 +440,13 @@ public: @@ -440,6 +440,13 @@ public:
static void convert_parent_class(uint8_t param_key, void *object_pointer,
const struct AP_Param::GroupInfo *group_info);
/*
fetch a parameter value based on the index within a group. This
is used to find the old value of a parameter that has been
removed from an object.
*/
static bool get_param_by_index(void *obj_ptr, uint8_t idx, ap_var_type old_ptype, void *pvalue);
/// Erase all variables in EEPROM.
///
static void erase_all(void);

Loading…
Cancel
Save