mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scripting: add param accesss helper
This commit is contained in:
parent
16753a51f4
commit
9dae370356
95
libraries/AP_Scripting/AP_Scripting_helpers.cpp
Normal file
95
libraries/AP_Scripting/AP_Scripting_helpers.cpp
Normal file
@ -0,0 +1,95 @@
|
|||||||
|
#include "AP_Scripting_helpers.h"
|
||||||
|
|
||||||
|
/// Fast param access via pointer helper class
|
||||||
|
|
||||||
|
// init by name
|
||||||
|
bool Parameter::init(const char *name)
|
||||||
|
{
|
||||||
|
vp = AP_Param::find(name, &vtype);
|
||||||
|
if (vp == nullptr) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// set a value
|
||||||
|
bool Parameter::set(float value)
|
||||||
|
{
|
||||||
|
if (vp == nullptr) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
switch (vtype) {
|
||||||
|
case AP_PARAM_INT8:
|
||||||
|
((AP_Int8 *)vp)->set(value);
|
||||||
|
return true;
|
||||||
|
case AP_PARAM_INT16:
|
||||||
|
((AP_Int16 *)vp)->set(value);
|
||||||
|
return true;
|
||||||
|
case AP_PARAM_INT32:
|
||||||
|
((AP_Int32 *)vp)->set(value);
|
||||||
|
return true;
|
||||||
|
case AP_PARAM_FLOAT:
|
||||||
|
((AP_Float *)vp)->set(value);
|
||||||
|
return true;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
// not a supported type
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// get a value by name
|
||||||
|
bool Parameter::get(float &value)
|
||||||
|
{
|
||||||
|
if (vp == nullptr) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
switch (vtype) {
|
||||||
|
case AP_PARAM_INT8:
|
||||||
|
value = ((AP_Int8 *)vp)->get();
|
||||||
|
break;
|
||||||
|
case AP_PARAM_INT16:
|
||||||
|
value = ((AP_Int16 *)vp)->get();
|
||||||
|
break;
|
||||||
|
|
||||||
|
case AP_PARAM_INT32:
|
||||||
|
value = ((AP_Int32 *)vp)->get();
|
||||||
|
break;
|
||||||
|
|
||||||
|
case AP_PARAM_FLOAT:
|
||||||
|
value = ((AP_Float *)vp)->get();
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
// not a supported type
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// set and save a value by name
|
||||||
|
bool Parameter::set_and_save(float value)
|
||||||
|
{
|
||||||
|
if (vp == nullptr) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
switch (vtype) {
|
||||||
|
case AP_PARAM_INT8:
|
||||||
|
((AP_Int8 *)vp)->set_and_save(value);
|
||||||
|
return true;
|
||||||
|
case AP_PARAM_INT16:
|
||||||
|
((AP_Int16 *)vp)->set_and_save(value);
|
||||||
|
return true;
|
||||||
|
case AP_PARAM_INT32:
|
||||||
|
((AP_Int32 *)vp)->set_and_save(value);
|
||||||
|
return true;
|
||||||
|
case AP_PARAM_FLOAT:
|
||||||
|
((AP_Float *)vp)->set_and_save(value);
|
||||||
|
return true;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
// not a supported type
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
22
libraries/AP_Scripting/AP_Scripting_helpers.h
Normal file
22
libraries/AP_Scripting/AP_Scripting_helpers.h
Normal file
@ -0,0 +1,22 @@
|
|||||||
|
#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);
|
||||||
|
|
||||||
|
// setters and getters
|
||||||
|
bool set(float value);
|
||||||
|
bool set_and_save(float value);
|
||||||
|
bool get(float &value);
|
||||||
|
|
||||||
|
private:
|
||||||
|
enum ap_var_type vtype;
|
||||||
|
AP_Param *vp;
|
||||||
|
};
|
||||||
|
|
Loading…
Reference in New Issue
Block a user