mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AP_Param: added ops needed for ArduCopter build
This commit is contained in:
parent
fbe7daa477
commit
fa493a0fb3
@ -375,6 +375,28 @@ public:
|
|||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/// bit ops on parameters
|
||||||
|
///
|
||||||
|
AP_ParamT<T,PT>& operator |=(const T &v) {
|
||||||
|
_value |= v;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
AP_ParamT<T,PT>& operator &=(const T &v) {
|
||||||
|
_value &= v;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
AP_ParamT<T,PT>& operator +=(const T &v) {
|
||||||
|
_value += v;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
AP_ParamT<T,PT>& operator -=(const T &v) {
|
||||||
|
_value -= v;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
/// AP_ParamT types can implement AP_Param::cast_to_float
|
/// AP_ParamT types can implement AP_Param::cast_to_float
|
||||||
///
|
///
|
||||||
float cast_to_float(void) {
|
float cast_to_float(void) {
|
||||||
|
Loading…
Reference in New Issue
Block a user