mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Param: fixed assignment handling and const
this fixes radio_min = radio_max = radio_trim = 0; in RC_Channel
This commit is contained in:
parent
5dcb64eec9
commit
fbe7daa477
@ -330,19 +330,19 @@ public:
|
|||||||
|
|
||||||
/// Value getter
|
/// Value getter
|
||||||
///
|
///
|
||||||
T get(void) const {
|
const T &get(void) const {
|
||||||
return _value;
|
return _value;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Value setter
|
/// Value setter
|
||||||
///
|
///
|
||||||
void set(T v) {
|
void set(const T &v) {
|
||||||
_value = v;
|
_value = v;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Combined set and save
|
/// Combined set and save
|
||||||
///
|
///
|
||||||
bool set_and_save(T v) {
|
bool set_and_save(const T &v) {
|
||||||
set(v);
|
set(v);
|
||||||
return save();
|
return save();
|
||||||
}
|
}
|
||||||
@ -364,19 +364,13 @@ public:
|
|||||||
///
|
///
|
||||||
/// This allows the class to be used in many situations where the value would be legal.
|
/// This allows the class to be used in many situations where the value would be legal.
|
||||||
///
|
///
|
||||||
operator T &() {
|
operator const T &() const {
|
||||||
return _value;
|
return _value;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Copy assignment from self does nothing.
|
|
||||||
///
|
|
||||||
AP_ParamT<T,PT>& operator= (AP_ParamT<T,PT>& v) {
|
|
||||||
return v;
|
|
||||||
}
|
|
||||||
|
|
||||||
/// Copy assignment from T is equivalent to ::set.
|
/// Copy assignment from T is equivalent to ::set.
|
||||||
///
|
///
|
||||||
AP_ParamT<T,PT>& operator= (T v) {
|
AP_ParamT<T,PT>& operator= (const T &v) {
|
||||||
_value = v;
|
_value = v;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user