mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Scripting: Parameter helper: add configured and set defualt
This commit is contained in:
parent
bd4aed80dc
commit
37db2c5d4d
@ -38,7 +38,7 @@ bool Parameter::set(float value)
|
||||
return false;
|
||||
}
|
||||
|
||||
// get a value by name
|
||||
// get value
|
||||
bool Parameter::get(float &value)
|
||||
{
|
||||
if (vp == nullptr) {
|
||||
@ -67,7 +67,7 @@ bool Parameter::get(float &value)
|
||||
return true;
|
||||
}
|
||||
|
||||
// set and save a value by name
|
||||
// set and save value
|
||||
bool Parameter::set_and_save(float value)
|
||||
{
|
||||
if (vp == nullptr) {
|
||||
@ -93,3 +93,37 @@ bool Parameter::set_and_save(float value)
|
||||
return false;
|
||||
}
|
||||
|
||||
// Check if param had been configured
|
||||
bool Parameter::configured()
|
||||
{
|
||||
if (vp == nullptr) {
|
||||
return false;
|
||||
}
|
||||
return vp->configured();
|
||||
}
|
||||
|
||||
// set default value
|
||||
bool Parameter::set_default(float value)
|
||||
{
|
||||
if (vp == nullptr) {
|
||||
return false;
|
||||
}
|
||||
switch (vtype) {
|
||||
case AP_PARAM_INT8:
|
||||
((AP_Int8 *)vp)->set_default(value);
|
||||
return true;
|
||||
case AP_PARAM_INT16:
|
||||
((AP_Int16 *)vp)->set_default(value);
|
||||
return true;
|
||||
case AP_PARAM_INT32:
|
||||
((AP_Int32 *)vp)->set_default(value);
|
||||
return true;
|
||||
case AP_PARAM_FLOAT:
|
||||
((AP_Float *)vp)->set_default(value);
|
||||
return true;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
// not a supported type
|
||||
return false;
|
||||
}
|
||||
|
@ -14,6 +14,8 @@ public:
|
||||
bool set(float value);
|
||||
bool set_and_save(float value);
|
||||
bool get(float &value);
|
||||
bool configured();
|
||||
bool set_default(float value);
|
||||
|
||||
private:
|
||||
enum ap_var_type vtype;
|
||||
|
Loading…
Reference in New Issue
Block a user