Save AP_Var's initial value as a default value, and add a function for restoring the default value.

Fix the AP_Var::lookup cache, which was very busted.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1448 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok 2011-01-05 09:25:07 +00:00
parent fe1311b2c4
commit 6c0fc63e61
2 changed files with 63 additions and 40 deletions

View File

@ -11,9 +11,11 @@
#include "AP_Var.h" #include "AP_Var.h"
const AP_Float AP_GainUnity(1.0); // Global constants exported
const AP_Float AP_GainNegativeUnity(-1.0); //
const AP_Float AP_Zero(0); AP_Float AP_FloatUnity(1.0);
AP_Float AP_FloatNegativeUnity(-1.0);
AP_Float AP_FloatZero(0);
// Constructor // Constructor
// //
@ -24,11 +26,12 @@ AP_Var::AP_Var(AP_VarAddress address,
_name(name), _name(name),
_scope(scope) _scope(scope)
{ {
// if the variable is interesting, link it into the list // link the variable into the list of known variables
if (_name || (_address != AP_VarNoAddress)) {
_link = _variables; _link = _variables;
_variables = this; _variables = this;
}
// reset the lookup cache
_lookupHintIndex = 0;
} }
// Destructor // Destructor
@ -37,18 +40,16 @@ AP_Var::AP_Var(AP_VarAddress address,
// //
AP_Var::~AP_Var(void) AP_Var::~AP_Var(void)
{ {
AP_Var *p;
// only do this for variables that were considered interesting
if (_name || (_address != AP_VarNoAddress)) {
// if we are at the head of the list - for variables // if we are at the head of the list - for variables
// recently constructed this is usually the case // recently constructed this is usually the case
if (_variables == this) { if (_variables == this) {
// remove us from the head of the list // remove us from the head of the list
_variables = _link; _variables = _link;
} else { } else {
// traverse the list looking for the entry that points to us // traverse the list looking for the entry that points to us
p = _variables; AP_Var *p = _variables;
while (p) { while (p) {
// is it pointing at us? // is it pointing at us?
if (p->_link == this) { if (p->_link == this) {
@ -60,7 +61,15 @@ AP_Var::~AP_Var(void)
p = p->_link; p = p->_link;
} }
} }
}
// reset the lookup cache
_lookupHintIndex = 0;
}
void
AP_Var::set_default(void)
{
// Default implementation of ::set_default does nothing
} }
// Copy the variable name to the provided buffer. // Copy the variable name to the provided buffer.
@ -172,12 +181,12 @@ AP_Var::lookup(int index)
} }
// search // search
while (index-- && p) // count until we hit the index or the end of the list while (i-- && p) // count until we hit the index or the end of the list
p = p->_link; p = p->_link;
// update the cache on hit // update the cache on hit
if (p) { if (p) {
_lookupHintIndex = i; _lookupHintIndex = index;
_lookupHint = p; _lookupHint = p;
} }

View File

@ -65,12 +65,18 @@ public:
/// Destructor /// Destructor
/// ///
/// Note that the linked-list removal can be inefficient when named variables /// Note that the linked-list removal can be inefficient when variables
/// are destroyed in an order other than the reverse of the order in which /// are destroyed in an order other than the reverse of the order in which
/// they are created. /// they are created. This is not a major issue for variables created
/// and destroyed automatically at block boundaries, and the creation and
/// destruction of variables by hand is generally discouraged.
/// ///
~AP_Var(void); ~AP_Var(void);
/// Set the variable to its default value
///
virtual void set_default(void);
/// Copy the variable's name, prefixed by any parent class names, to a buffer. /// Copy the variable's name, prefixed by any parent class names, to a buffer.
/// ///
/// If the variable has no name, the buffer will contain an empty string. /// If the variable has no name, the buffer will contain an empty string.
@ -224,12 +230,13 @@ public:
/// @param name An optional name by which the variable may be known. /// @param name An optional name by which the variable may be known.
/// @param varClass An optional class that the variable may be a member of. /// @param varClass An optional class that the variable may be a member of.
/// ///
AP_VarT<T>(T initialValue = 0, AP_VarT<T>(T defaultValue = 0,
AP_VarAddress address = AP_VarNoAddress, AP_VarAddress address = AP_VarNoAddress,
const prog_char *name = NULL, const prog_char *name = NULL,
AP_VarScope *scope = NULL) : AP_VarScope *scope = NULL) :
AP_Var(address, name, scope), AP_Var(address, name, scope),
_value(initialValue) _value(defaultValue),
_defaultValue(defaultValue)
{ {
} }
@ -249,6 +256,9 @@ public:
return sizeof(T); return sizeof(T);
} }
/// Restore the variable to its default value
virtual void set_default(void) { _value = _defaultValue; }
/// Value getter /// Value getter
/// ///
T get(void) const { return _value; } T get(void) const { return _value; }
@ -267,11 +277,12 @@ public:
/// ///
AP_VarT<T>& operator=(AP_VarT<T>& v) { return v; } AP_VarT<T>& operator=(AP_VarT<T>& v) { return v; }
/// Copy assignment from /// Copy assignment from T
AP_VarT<T>& operator=(T v) { _value = v; return *this; } AP_VarT<T>& operator=(T v) { _value = v; return *this; }
protected: protected:
T _value; T _value;
T _defaultValue;
}; };
@ -297,11 +308,11 @@ class AP_Float16 : public AP_Float
public: public:
/// Constructor mimics AP_Float::AP_Float() /// Constructor mimics AP_Float::AP_Float()
/// ///
AP_Float16(float initialValue = 0, AP_Float16(float defaultValue = 0,
AP_VarAddress address = AP_VarNoAddress, AP_VarAddress address = AP_VarNoAddress,
const prog_char *name = NULL, const prog_char *name = NULL,
AP_VarScope *scope = NULL) : AP_VarScope *scope = NULL) :
AP_Float(initialValue, address, name, scope) AP_Float(defaultValue, address, name, scope)
{ {
} }
@ -332,8 +343,11 @@ public:
}; };
/// Some convenient constant AP_Vars. /// Some convenient constant AP_Vars.
extern const AP_Float AP_FloatUnity; ///
extern const AP_Float AP_FloatNegativeUnity; /// @todo Work out why these can't be const and fix if possible.
extern const AP_Float AP_FloatZero; ///
extern AP_Float AP_FloatUnity;
extern AP_Float AP_FloatNegativeUnity;
extern AP_Float AP_FloatZero;
#endif // AP_Var_H #endif // AP_Var_H