AP_Param: added ops needed for ArduCopter build

This commit is contained in:
Andrew Tridgell 2013-04-18 11:12:46 +10:00
parent fbe7daa477
commit fa493a0fb3

View File

@ -375,6 +375,28 @@ public:
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
///
float cast_to_float(void) {