Browse Source

AP_Param: params always use set method

apm_2208
Iampete1 3 years ago committed by Peter Hall
parent
commit
59d75813cc
  1. 29
      libraries/AP_Param/AP_Param.h

29
libraries/AP_Param/AP_Param.h

@ -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 {

Loading…
Cancel
Save