mirror of https://github.com/ArduPilot/ardupilot
AP_Param: added set() to AP_Enum
This commit is contained in:
parent
470b9638ea
commit
4899ec9457
|
@ -1018,6 +1018,9 @@ public:
|
||||||
operator const eclass () const {
|
operator const eclass () const {
|
||||||
return (eclass)_value;
|
return (eclass)_value;
|
||||||
}
|
}
|
||||||
|
void set(eclass v) {
|
||||||
|
AP_Int8::set(int8_t(v));
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
template<typename eclass>
|
template<typename eclass>
|
||||||
|
@ -1027,4 +1030,7 @@ public:
|
||||||
operator const eclass () const {
|
operator const eclass () const {
|
||||||
return (eclass)_value;
|
return (eclass)_value;
|
||||||
}
|
}
|
||||||
|
void set(eclass v) {
|
||||||
|
AP_Int16::set(int16_t(v));
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue