mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
AP_Param: added find_by_index()
This commit is contained in:
parent
3077de0d33
commit
e761645e24
@ -579,6 +579,22 @@ AP_Param::find(const char *name, enum ap_var_type *ptype)
|
|||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Find a variable by index. Note that this is quite slow.
|
||||||
|
//
|
||||||
|
AP_Param *
|
||||||
|
AP_Param::find_by_index(uint16_t idx, enum ap_var_type *ptype)
|
||||||
|
{
|
||||||
|
ParamToken token;
|
||||||
|
AP_Param *ap;
|
||||||
|
uint16_t count=0;
|
||||||
|
for (ap=AP_Param::first(&token, ptype);
|
||||||
|
ap && count < idx;
|
||||||
|
ap=AP_Param::next_scalar(&token, ptype)) {
|
||||||
|
count++;
|
||||||
|
}
|
||||||
|
return ap;
|
||||||
|
}
|
||||||
|
|
||||||
// Save the variable to EEPROM, if supported
|
// Save the variable to EEPROM, if supported
|
||||||
//
|
//
|
||||||
bool AP_Param::save(void)
|
bool AP_Param::save(void)
|
||||||
|
@ -132,6 +132,15 @@ public:
|
|||||||
///
|
///
|
||||||
static AP_Param * find(const char *name, enum ap_var_type *ptype);
|
static AP_Param * find(const char *name, enum ap_var_type *ptype);
|
||||||
|
|
||||||
|
/// Find a variable by index.
|
||||||
|
///
|
||||||
|
///
|
||||||
|
/// @param idx The index of the variable
|
||||||
|
/// @return A pointer to the variable, or NULL if
|
||||||
|
/// it does not exist.
|
||||||
|
///
|
||||||
|
static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype);
|
||||||
|
|
||||||
/// Save the current value of the variable to EEPROM.
|
/// Save the current value of the variable to EEPROM.
|
||||||
///
|
///
|
||||||
/// @return True if the variable was saved successfully.
|
/// @return True if the variable was saved successfully.
|
||||||
|
Loading…
Reference in New Issue
Block a user