AP_Param: params always use set method

This commit is contained in:
Iampete1 2022-07-05 04:08:56 +01:00 committed by Peter Hall
parent 2241766ed6
commit 59d75813cc
1 changed files with 0 additions and 29 deletions

View File

@ -893,35 +893,6 @@ public:
return _value; return _value;
} }
/// Copy assignment from T is equivalent to ::set.
///
AP_ParamT<T,PT>& operator= (const T &v) {
_value = v;
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) const { float cast_to_float(void) const {