From fbe7daa47784281598b70ef26f50600518202a92 Mon Sep 17 00:00:00 2001 From: tobias Date: Thu, 18 Apr 2013 10:52:40 +1000 Subject: [PATCH] AP_Param: fixed assignment handling and const this fixes radio_min = radio_max = radio_trim = 0; in RC_Channel --- libraries/AP_Param/AP_Param.h | 16 +++++----------- 1 file changed, 5 insertions(+), 11 deletions(-) diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index cbcc89b943..7784d12915 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -330,19 +330,19 @@ public: /// Value getter /// - T get(void) const { + const T &get(void) const { return _value; } /// Value setter /// - void set(T v) { + void set(const T &v) { _value = v; } /// Combined set and save /// - bool set_and_save(T v) { + bool set_and_save(const T &v) { set(v); return save(); } @@ -364,19 +364,13 @@ public: /// /// This allows the class to be used in many situations where the value would be legal. /// - operator T &() { + operator const T &() const { return _value; } - /// Copy assignment from self does nothing. - /// - AP_ParamT& operator= (AP_ParamT& v) { - return v; - } - /// Copy assignment from T is equivalent to ::set. /// - AP_ParamT& operator= (T v) { + AP_ParamT& operator= (const T &v) { _value = v; return *this; }