Add a flags byte to variables, and implement a "no auto load" bit that opts variables out of load_all / save_all.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1449 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok 2011-01-05 17:56:46 +00:00
parent 6c0fc63e61
commit 9e79b78d2a
2 changed files with 35 additions and 12 deletions

View File

@ -21,10 +21,12 @@ AP_Float AP_FloatZero(0);
// //
AP_Var::AP_Var(AP_VarAddress address, AP_Var::AP_Var(AP_VarAddress address,
const prog_char *name, const prog_char *name,
const AP_VarScope *scope) : const AP_VarScope *scope,
Flags flags) :
_address(address), _address(address),
_name(name), _name(name),
_scope(scope) _scope(scope),
_flags(flags)
{ {
// link the variable into the list of known variables // link the variable into the list of known variables
_link = _variables; _link = _variables;
@ -201,7 +203,8 @@ AP_Var::save_all(void)
AP_Var *p = _variables; AP_Var *p = _variables;
while (p) { while (p) {
p->save(); if (!p->has_flags(NO_AUTO_LOAD))
p->save();
p = p->_link; p = p->_link;
} }
} }
@ -214,7 +217,8 @@ AP_Var::load_all(void)
AP_Var *p = _variables; AP_Var *p = _variables;
while (p) { while (p) {
p->load(); if (!p->has_flags(NO_AUTO_LOAD))
p->load();
p = p->_link; p = p->_link;
} }
} }

View File

@ -51,6 +51,14 @@ public:
/// ///
static const size_t AP_VarMaxSize = 16; static const size_t AP_VarMaxSize = 16;
/// Optional flags affecting the behavior and usage of the variable.
///
enum Flags {
NO_FLAGS = 0,
NO_AUTO_LOAD = (1<<0), ///< will not be loaded by ::load_all or saved by ::save_all
NO_IMPORT = (1<<1) ///< new values must not be imported from e.g. a GCS
};
/// Constructor /// Constructor
/// ///
/// @param name An optional name by which the variable may be known. /// @param name An optional name by which the variable may be known.
@ -61,7 +69,8 @@ public:
/// ///
AP_Var(AP_VarAddress address = AP_VarNoAddress, AP_Var(AP_VarAddress address = AP_VarNoAddress,
const prog_char *name = NULL, const prog_char *name = NULL,
const AP_VarScope *scope = NULL); const AP_VarScope *scope = NULL,
Flags flags = NO_FLAGS);
/// Destructor /// Destructor
/// ///
@ -123,11 +132,19 @@ public:
/// ///
static void load_all(void); static void load_all(void);
/// Test for flags that may be set.
///
/// @param flagval Flag or flags to be tested
/// @returns True if all of the bits in flagval are set in the flags.
///
bool has_flags(Flags flagval) const { return (_flags & flagval) == flagval; }
private: private:
const AP_VarAddress _address; const AP_VarAddress _address;
const prog_char *_name; const prog_char *_name;
const AP_VarScope * const _scope; const AP_VarScope * const _scope;
AP_Var *_link; AP_Var *_link;
uint8_t _flags;
/// Do the arithmetic required to compute the variable's address in EEPROM /// Do the arithmetic required to compute the variable's address in EEPROM
/// ///
@ -233,8 +250,9 @@ public:
AP_VarT<T>(T defaultValue = 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), Flags flags = NO_FLAGS) :
AP_Var(address, name, scope, flags),
_value(defaultValue), _value(defaultValue),
_defaultValue(defaultValue) _defaultValue(defaultValue)
{ {
@ -308,11 +326,12 @@ class AP_Float16 : public AP_Float
public: public:
/// Constructor mimics AP_Float::AP_Float() /// Constructor mimics AP_Float::AP_Float()
/// ///
AP_Float16(float defaultValue = 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(defaultValue, address, name, scope) Flags flags = NO_FLAGS) :
AP_Float(defaultValue, address, name, scope, flags)
{ {
} }