AP_Param: make things a bit more efficient

This commit is contained in:
Andrew Tridgell 2013-04-21 22:23:46 +10:00
parent 3d325043b0
commit 01a4fabf9e

View File

@ -438,7 +438,7 @@ public:
/// Value getter /// Value getter
/// ///
T get(void) const { const T &get(void) const {
return _value; return _value;
} }
@ -459,16 +459,10 @@ 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_ParamV<T,PT>& operator =(AP_ParamV<T,PT>& v) {
return v;
}
/// Copy assignment from T is equivalent to ::set. /// Copy assignment from T is equivalent to ::set.
/// ///
AP_ParamV<T,PT>& operator =(T v) { AP_ParamV<T,PT>& operator =(T v) {
@ -531,12 +525,6 @@ public:
} }
} }
/// Copy assignment from self does nothing.
///
AP_ParamA<T,N,PT>& operator= (AP_ParamA<T,N,PT>& v) {
return v;
}
protected: protected:
T _value[N]; T _value[N];
}; };