mirror of https://github.com/ArduPilot/ardupilot
96 lines
1.9 KiB
C++
96 lines
1.9 KiB
C++
|
#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;
|
||
|
}
|
||
|
|