Implement a cast_to_float method for convenience; at a cost of a couple of bytes in the vtable this will save many callers having to play type introspection games.

It might be possible to implement a set of virtual cast operator overrides, but only float lets us return NAN to indicate that a cast can't be made, so for now we'll stick with just this one.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1614 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok 2011-02-08 10:17:45 +00:00
parent 56eea84a89
commit 107e06d849
2 changed files with 33 additions and 1 deletions

View File

@ -19,6 +19,7 @@ extern "C" { extern void delay(unsigned long); }
#include <AP_Common.h> #include <AP_Common.h>
#include <math.h>
#include <string.h> #include <string.h>
// Global constants exported for general use. // Global constants exported for general use.
@ -313,6 +314,14 @@ AP_Var::key(void)
return var_header.key; return var_header.key;
} }
// Default implementation of cast_to_float, which always fails.
//
float
AP_Var::cast_to_float(void) const
{
return NAN;
}
// Return the next variable in the global list. // Return the next variable in the global list.
// //
AP_Var * AP_Var *

View File

@ -335,6 +335,17 @@ public:
/// ///
Key key(void); Key key(void);
/// Casts the value to float, if possible.
///
/// This is a convenience method for code that would rather not try to
/// meta-cast to the various subtypes. It cannot guarantee that a useful value
/// will be returned; the caller must check the returned value against NAN
/// before using it.
///
/// @return The value cast to float, or NAN if it cannot be cast.
///
virtual float cast_to_float() const;
private: private:
AP_Var_group *_group; ///< Group that the variable may be a member of AP_Var_group *_group; ///< Group that the variable may be a member of
AP_Var *_link; ///< linked list pointer to next variable AP_Var *_link; ///< linked list pointer to next variable
@ -547,10 +558,23 @@ public:
return *this; return *this;
} }
/// AP_VarT types can implement AP_Var::cast_to_float
///
virtual float cast_to_float() const;
protected: protected:
T _value; T _value;
}; };
// Implement AP_Var::cast_to_float.
//
template<typename T>
float
AP_VarT<T>::cast_to_float() const
{
return (float)_value;
}
/// Template class for array variables. /// Template class for array variables.
/// ///
/// Objects created using this template behave like arrays of the type T, /// Objects created using this template behave like arrays of the type T,
@ -671,7 +695,6 @@ protected:
T _value[N]; T _value[N];
}; };
/// Convenience macro for defining instances of the AP_VarT template. /// Convenience macro for defining instances of the AP_VarT template.
/// ///
#define AP_VARDEF(_t, _n) typedef AP_VarT<_t> AP_##_n; #define AP_VARDEF(_t, _n) typedef AP_VarT<_t> AP_##_n;