mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: added a method for example programs to set parameters in objects
This commit is contained in:
parent
0dcd0e600b
commit
3474da6c97
@ -819,6 +819,24 @@ void AP_Param::setup_object_defaults(const void *object_pointer, const struct Gr
|
||||
}
|
||||
}
|
||||
|
||||
// set a value directly in an object. This should only be used by
|
||||
// example code, not by mainline vehicle code
|
||||
void AP_Param::set_object_value(const void *object_pointer,
|
||||
const struct GroupInfo *group_info,
|
||||
const char *name, float value)
|
||||
{
|
||||
uintptr_t base = (uintptr_t)object_pointer;
|
||||
uint8_t type;
|
||||
for (uint8_t i=0;
|
||||
(type=PGM_UINT8(&group_info[i].type)) != AP_PARAM_NONE;
|
||||
i++) {
|
||||
if (strcmp(name, group_info[i].name) == 0 && type <= AP_PARAM_FLOAT) {
|
||||
void *ptr = (void *)(base + PGM_UINT16(&group_info[i].offset));
|
||||
set_value((enum ap_var_type)type, ptr, value);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// load default values for all scalars in a sketch. This does not
|
||||
// recurse into sub-objects
|
||||
|
@ -199,6 +199,12 @@ public:
|
||||
// load default values for scalars in a group
|
||||
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info);
|
||||
|
||||
// set a value directly in an object. This should only be used by
|
||||
// example code, not by mainline vehicle code
|
||||
static void set_object_value(const void *object_pointer,
|
||||
const struct GroupInfo *group_info,
|
||||
const char *name, float value);
|
||||
|
||||
// load default values for all scalars in the main sketch. This
|
||||
// does not recurse into the sub-objects
|
||||
static void setup_sketch_defaults(void);
|
||||
|
Loading…
Reference in New Issue
Block a user