ardupilot/libraries/AP_Scripting/AP_Scripting_helpers.h

28 lines
551 B
C
Raw Normal View History

2021-01-02 11:34:09 -04:00
#pragma once
#include <AP_Param/AP_Param.h>
/// Fast param access via pointer helper
class Parameter
{
public:
// init to param by name
bool init(const char *name);
// init by token, to get the value of old params
bool init_by_info(uint16_t key, uint32_t group_element, enum ap_var_type type);
2021-01-02 11:34:09 -04:00
// setters and getters
bool set(float value);
bool set_and_save(float value);
bool get(float &value);
bool configured();
bool set_default(float value);
2021-01-02 11:34:09 -04:00
private:
enum ap_var_type vtype;
AP_Param *vp;
};