mirror of https://github.com/ArduPilot/ardupilot
AP_Param: params always use set method
This commit is contained in:
parent
2241766ed6
commit
59d75813cc
|
@ -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…
Reference in New Issue