I never liked the plan that variable groups could only be statically scoped; it was much too fragile. These changes address that issue by splitting the global variable list into two lists, one for standalone variables (including groups), and one for variables that are members of a group.

Now a variable belonging to a group can safely be constructed before the group it belongs to, and the group can be destroyed before its member variables.  This greatly simplifies the AP_Var constructor(s).

Remove the lookup-by-index and lookup-by-key interfaces to AP_Var and replace them with first/next interfaces for all variables, and for variables belonging to a specific group.  Document their usage.  Add an accessor for the key associated with a variable so that search-by-key can be performed by a consumer.  Throw away the lookup cache implementation, as it's not required anymore.

Re-layout the EEPROM variable header and tweak the EEPROM space allocator so that it's more resistant to interruptions during variable save.

Fix the global constants so that they work.

Add an interface for erasing all variables in EEPROM (only writes one byte).

Fix unit tests so that they work with the changed interfaces.  Also tweak the unit test framework so that it doesn't inline all its code.  This is a WIP - many more tests need to be written still.


git-svn-id: https://arducopter.googlecode.com/svn/trunk@1531 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok@gmail.com 2011-01-23 06:52:59 +00:00
parent 8317c090da
commit 1a2ce433e1
3 changed files with 460 additions and 319 deletions

View File

@ -11,114 +11,108 @@
#include "AP_Var.h"
// Global constants exported
// Global constants exported for general use.
//
AP_Float AP_Float_unity(1.0);
AP_Float AP_Float_negative_unity(-1.0);
AP_Float AP_Float_zero(0);
AP_Float AP_Float_unity ( 1.0, AP_Var::k_key_none, NULL, AP_Var::k_flag_unlisted);
AP_Float AP_Float_negative_unity(-1.0, AP_Var::k_key_none, NULL, AP_Var::k_flag_unlisted);
AP_Float AP_Float_zero ( 0.0, AP_Var::k_key_none, NULL, AP_Var::k_flag_unlisted);
// Local state for the lookup interface
//
AP_Var *AP_Var::_variables = NULL;
AP_Var *AP_Var::_lookup_hint = NULL;
int AP_Var::_lookup_hint_index = 0;
uint16_t AP_Var::_tail_sentinel;
bool AP_Var::_EEPROM_scanned;
// Constructor
// Static member variables for AP_Var.
//
AP_Var::AP_Var(Key key, const prog_char *name, AP_Var_group *group, Flags flags) :
_group(group),
_key(key | k_not_located),
AP_Var *AP_Var::_variables;
AP_Var *AP_Var::_grouped_variables;
uint16_t AP_Var::_tail_sentinel;
bool AP_Var::_EEPROM_scanned;
// Constructor for standalone variables
//
AP_Var::AP_Var(Key key, const prog_char *name, Flags flags) :
_group(NULL),
_key(key | k_key_not_located),
_name(name),
_flags(flags)
{
AP_Var *vp;
// Insert the variable or group into the list of known variables.
// Insert the variable or group into the list of known variables, unless
// it wants to be unlisted.
//
// Variables belonging to a group are inserted into the list following the group,
// which may not itself yet be in the global list. Thus groups must be
// statically constructed (which guarantees _link will be zero due to the BSS
// being cleared).
//
if (group) {
// Sort the variable into the list of variables following the group itself.
vp = group;
for (;;) {
// if there are no more entries, we insert at the end
if (vp->_link == NULL)
break;
// if the next entry in the list is a group, insert before it
if (meta_type_equivalent(this, vp->_link))
break;
// if the next entry has a higher index, insert before it
if ((vp->_link->_key & k_key_mask) > key)
break;
vp = vp->_link;
}
// insert into the group's list
_link = vp->_link;
vp->_link = this;
} else {
// Insert directly at the head of the list. Take into account the possibility
// that what is being inserted is a group that already has variables sorted after it.
//
vp = this;
if (meta_cast<AP_Var_group>(this) != NULL) {
// we are inserting a group, scan to the end of any list of pre-attached variables
while (vp->_link != NULL)
vp = vp->_link;
}
// insert at the head of the global list
vp->_link = _variables;
if (!has_flags(k_flag_unlisted)) {
_link = _variables;
_variables = this;
}
}
// reset the lookup cache
_lookup_hint_index = 0;
// Constructor for variables in a group
//
AP_Var::AP_Var(AP_Var_group *group, Key index, const prog_char *name, Flags flags) :
_group(group),
_key(index),
_name(name),
_flags(flags)
{
AP_Var **vp;
// Sort the variable into the list of group-member variables.
//
// This list is kept sorted so that groups can traverse forwards along
// it in order to enumerate their members in key order.
//
// We use a pointer-to-pointer insertion technique here; vp points
// to the pointer to the node that we are considering inserting in front of.
//
vp = &_grouped_variables;
while (*vp != NULL) {
if ((*vp)->_key > _key) {
break;
}
vp = &((*vp)->_link);
}
_link = *vp;
*vp = this;
}
// Destructor
//
// Removes named variables from the list.
//
AP_Var::~AP_Var(void)
{
AP_Var **vp;
// Groups can only be destroyed when they have no members.
// Determine which list the variable may be in.
// If the variable is a group member and the group has already
// been destroyed, it may not be in any list.
//
// If this is a group with one or more members, _link is not NULL
// and _link->group is this.
//
if ((_link != NULL) && (_link->_group == this))
return;
if (_group) {
vp = &_grouped_variables;
} else {
vp = &_variables;
}
// Walk the list and remove this when we find it.
//
vp = &_variables;
while (*vp != NULL) {
// pointer pointing at this?
// Scan the list and remove this if we find it
while (*vp) {
if (*vp == this) {
*vp = _link;
break;
}
// address of next entry's link pointer
vp = &((*vp)->_link);
}
// reset the lookup cache
_lookup_hint_index = 0;
// If we are destroying a group, remove all its variables from the list
//
if (has_flags(k_flag_is_group)) {
// Scan the list and remove any variable that has this as its group
vp = &_grouped_variables;
while (*vp) {
// Does the variable claim us as its group?
if ((*vp)->_group == this) {
*vp = (*vp)->_link;
continue;
}
vp = &((*vp)->_link);
}
}
}
// Copy the variable's whole name to the supplied buffer.
@ -137,7 +131,7 @@ void AP_Var::copy_name(char *buffer, size_t buffer_size) const
//
bool AP_Var::save(void)
{
uint8_t vbuf[k_max_size];
uint8_t vbuf[k_size_max];
size_t size;
// if the variable is a group member, save the group
@ -164,7 +158,7 @@ bool AP_Var::save(void)
//
bool AP_Var::load(void)
{
uint8_t vbuf[k_max_size];
uint8_t vbuf[k_size_max];
size_t size;
// if the variable is a group member, load the group
@ -193,42 +187,6 @@ bool AP_Var::load(void)
return true;
}
//
// Lookup interface for variables.
//
AP_Var *
AP_Var::lookup_by_index(int index)
{
AP_Var *p;
int i;
// establish initial search state
//
if (_lookup_hint_index && // we have a cached hint (cannot use a hint index of zero)
(index >= _lookup_hint_index)) { // the desired index is at or after the hint
p = _lookup_hint; // start at the hint point
i = index - _lookup_hint_index; // count only the distance from the hint to the index
} else {
p = _variables; // start at the beginning of the list
i = index; // count to the index
}
// search
while (p && i--) { // count until we hit the index or the end of the list
p = p->_link;
}
// update the cache on hit
if (p) {
_lookup_hint_index = index;
_lookup_hint = p;
}
return p;
}
// Save all variables that don't opt out.
//
//
@ -238,7 +196,7 @@ bool AP_Var::save_all(void)
AP_Var *p = _variables;
while (p) {
if (!p->has_flags(k_no_auto_load) && // not opted out
if (!p->has_flags(k_flag_no_auto_load) && // not opted out
!(p->_group)) { // not saved with a group
if (!p->save()) {
@ -258,7 +216,7 @@ bool AP_Var::load_all(void)
AP_Var *p = _variables;
while (p) {
if (!p->has_flags(k_no_auto_load) && // not opted out
if (!p->has_flags(k_flag_no_auto_load) && // not opted out
!(p->_group)) { // not loaded with a group
if (!p->load()) {
@ -270,40 +228,91 @@ bool AP_Var::load_all(void)
return result;
}
// Scan the list of variables for a matching key.
// Erase all variables in EEPROM.
//
AP_Var *
AP_Var::_lookup_by_key(Key key)
void
AP_Var::erase_all()
{
uint8_t c;
// overwrite the first byte of the header, invalidating the EEPROM
//
c = 0xff;
eeprom_write_byte(&c, 0);
}
// Return the key for a variable.
//
AP_Var::Key
AP_Var::key(void)
{
AP_Var *p;
Key nl_key;
Var_header var_header;
nl_key = key | k_not_located; // key to expect in memory
if (_group) { // group members don't have keys
return k_key_none;
}
if (_key && k_key_not_located) { // if not located, key is in memory
return _key & k_key_mask;
}
// scan the list of variables
p = _variables;
while (p) {
// read key from EEPROM
eeprom_read_block(&var_header, (void *)_key, sizeof(var_header));
return var_header.key;
}
// if the variable is a group member, it cannot be found by key search
if (p->_group) {
continue;
// Return the next variable in the global list.
//
AP_Var *
AP_Var::next(void)
{
// If there is a variable after this one, return it.
//
if (_link)
return _link;
// If we are at the end of the _variables list, _group will be NULL; in that
// case, move to the _grouped_variables list.
//
if (!_group) {
return _grouped_variables;
}
// We must be at the end of the _grouped_variables list, nothing remains.
//
return NULL;
}
// Return the first variable that is a member of the group.
//
AP_Var *
AP_Var::first_member(AP_Var_group *group)
{
AP_Var **vp;
vp = &_grouped_variables;
while (*vp) {
if ((*vp)->_group == group) {
return *vp;
}
vp = &((*vp)->_link);
}
return NULL;
}
// has this variable been located?
if (p->_key & k_not_located) {
// does the variable have the non-located form of the key?
if (p->_key == nl_key)
return p; // found it
} else {
// read the header from EEPROM and compare it with the search key
eeprom_read_block(&var_header, (void *)p->_key, sizeof(var_header));
if (var_header.key == key)
return p;
// Return the next variable that is a member of the same group.
AP_Var *
AP_Var::next_member()
{
AP_Var *vp;
vp = _link;
while (vp) {
if (vp->_group == _group) {
return vp;
}
// try the next variable
p = p->_link;
vp = vp->_link;
}
return NULL;
}
@ -337,7 +346,7 @@ bool AP_Var::_EEPROM_scan(void)
eeprom_read_block(&var_header, (void *)_tail_sentinel, sizeof(var_header));
// if the header is for the sentinel, scanning is complete
if (var_header.key == k_tail_sentinel)
if (var_header.key == k_key_sentinel)
break;
// if the variable plus the sentinel would extend past the end of EEPROM, we are done
@ -345,19 +354,26 @@ bool AP_Var::_EEPROM_scan(void)
_tail_sentinel + // current position
sizeof(ee_header) + // header for this variable
var_header.size + 1 + // data for this variable
sizeof(ee_header))) // header for sentinel
sizeof(ee_header))) { // header for sentinel
break;
}
// look for a variable with this key
vp = _lookup_by_key(var_header.key);
if (vp) {
// adjust the variable's key to point to this entry
vp->_key = _tail_sentinel;
vp = _variables;
while (vp) {
if (vp->key() == var_header.key) {
// adjust the variable's key to point to this entry
vp->_key = _tail_sentinel;
break;
}
vp = vp->_link;
}
// move to the next variable header
_tail_sentinel += sizeof(var_header) + var_header.size + 1;
}
// Scanning is complete
_EEPROM_scanned = true;
return true;
}
@ -367,41 +383,50 @@ bool AP_Var::_EEPROM_scan(void)
bool AP_Var::_EEPROM_locate(bool allocate)
{
Var_header var_header;
Key new_location;
size_t size;
// Is it a group member, or does it have a no-location key?
//
if (_group || (_key == k_key_none)) {
return false; // it is/does, and thus it has no location
}
// Has the variable already been located?
if (!(_key & k_not_located)) {
//
if (!(_key & k_key_not_located)) {
return true; // it has
}
// Does it have a no-key key?
if (_key == k_no_key) {
return false; // it does, and thus it has no location
}
// If the EEPROM has not been scanned, try that now
// If the EEPROM has not been scanned, try that now.
//
if (!_EEPROM_scanned) {
_EEPROM_scan();
}
// If not located and not permitted to allocate, we have failed
if ((_key & k_not_located) && !allocate) {
// If not located and not permitted to allocate, we have failed.
//
if ((_key & k_key_not_located) && !allocate) {
return false;
}
// Ask the serializer for the size of the thing we are allocating, and fail
// if it is too large or if it has no size
// if it is too large or if it has no size, as we will not be able to allocate
// space for it.
//
size = serialize(NULL, 0);
if ((0 == size) || (size > k_max_size))
if ((size == 0) || (size > k_size_max))
return false;
// Make sure there will be space in the EEPROM for the variable, its
// header and the new tail sentinel
// header and the new tail sentinel.
//
if ((_tail_sentinel + size + sizeof(Var_header) * 2) > k_EEPROM_size)
return false;
// If there is no data in the EEPROM, write the header and move the
// sentinel
// sentinel.
//
if (0 == _tail_sentinel) {
EEPROM_header ee_header;
@ -414,23 +439,28 @@ bool AP_Var::_EEPROM_locate(bool allocate)
_tail_sentinel = sizeof(ee_header);
}
// Write a new sentinel first
var_header.key = k_tail_sentinel;
var_header.size = 0;
eeprom_write_block(&var_header, (void *)(_tail_sentinel + sizeof(Var_header) + size), sizeof(var_header));
// Write the header for the block we have just located
var_header.key = _key & k_key_mask;
var_header.size = size - 1;
eeprom_write_block(&var_header, (void *)_tail_sentinel, sizeof(Var_header));
// Save the located address for the variable
_key = _tail_sentinel + sizeof(Var_header);
// Update to the new tail sentinel
// Save the location we are going to insert at, and compute the new
// tail sentinel location.
//
_tail_sentinel += sizeof(Var_header) + size;
new_location = _tail_sentinel;
// We have successfully allocated space and thus located the variable
// Write the new sentinel first. If we are interrupted during this operation
// the old sentinel will still correctly terminate the EEPROM image.
//
var_header.key = k_key_sentinel;
var_header.size = 0;
eeprom_write_block(&var_header, (void *)_tail_sentinel, sizeof(var_header));
// Write the header for the block we have just located, claiming the EEPROM space.
//
var_header.key = key();
var_header.size = size - 1;
eeprom_write_block(&var_header, (void *)new_location, sizeof(Var_header));
// We have successfully allocated space and thus located the variable.
//
_key = new_location;
return true;
}
@ -455,11 +485,11 @@ AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_seriali
// Traverse the list of group members, serializing each in order
//
vp = next();
vp = first_member(this);
bp = (uint8_t *)buf;
resid = buf_size;
total_size = 0;
while (vp->group() == this) {
while (vp) {
// (un)serialise the group member
if (do_serialize) {
@ -485,7 +515,7 @@ AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_seriali
bp += size;
}
vp = vp->next();
vp = vp->next_member();
}
return total_size;
}

View File

@ -56,101 +56,134 @@ public:
/// Storage key for variables that are saved in EEPROM.
///
/// The key is used to associate a known variable in memory
/// with storage for the variable in the EEPROM. When the
/// variable's storage is located in EEPROM, the key value is
/// replaced with an EEPROM address.
/// with storage for the variable in the EEPROM.
///
/// When the variable is saved to EEPROM, a header is attached
/// which contains the key along with other details.
/// At creation time, the _key value has the k_key_not_located bit
/// set, and its value is an ordinal uniquely identifying the
/// variable. Once the address of the variable in EEPROM is known,
/// either as a result of scanning or due to allocation of new
/// space in the EEPROM, the k_key_not_located bit will be cleared
/// and the _key value gives the offset into the EEPROM where
/// the variable's header can be found.
///
typedef uint16_t Key;
/// The header prepended to a variable stored in EEPROM
/// This header is prepended to a variable stored in EEPROM.
///
/// Note that the size value is the first element in the header.
/// The sentinel entry marking the end of the EEPROM is always written
/// before updating the header of a new variable at the end of EEPROM.
/// This provides protection against corruption that might be caused
/// if the update process is interrupted.
///
struct Var_header {
/// The size of the variable, minus one.
/// This allows a variable to be anything from one to 32 bytes long.
/// This allows a variable or group to be anything from one to 32 bytes long.
///
uint16_t size:5;
/// The key assigned to the variable.
///
uint16_t key:8;
uint8_t size:5;
/// Spare bits, currently unused
///
/// @todo One could be a parity bit?
///
uint16_t spare:3;
uint8_t spare:3;
/// The key assigned to the variable.
///
uint8_t key;
};
/// An key that indicates that a variable is not to be saved to EEPROM.
/// A key value that indicates that a variable is not to be saved to EEPROM.
///
/// As the value has all bits set to 1, it's not a legal EEPROM address for any
/// EEPROM smaller than 64K (and it's too big to fit the Var_header::key field).
///
/// This value is normally the default.
///
static const Key k_no_key = 0xffff;
static const Key k_key_none = 0xffff;
/// A key that has this bit set is still a key; if it has been cleared then
/// the key's value is actually an address in EEPROM.
///
static const Key k_not_located = (Key)1 << 15;
static const Key k_key_not_located = (Key)1 << 15;
/// Key assigned to the terminal entry in EEPROM.
///
static const Key k_tail_sentinel = 0xff;
static const Key k_key_sentinel = 0xff;
/// A bitmask that removes any control bits from a key giving just the
/// value.
///
static const Key k_key_mask = ~(k_not_located);
static const Key k_key_mask = ~(k_key_not_located);
/// The largest variable that will be saved to EEPROM.
/// This affects the amount of stack space that is required by the ::save, ::load,
/// ::save_all and ::load_all functions. It should match the maximum size that can
/// be encoded in the Var_header::size field.
///
static const size_t k_max_size = 32;
static const size_t k_size_max = 32;
/// Optional flags affecting the behavior and usage of the variable.
///
enum Flags {
k_no_flags = 0,
typedef uint8_t Flags;
static const Flags k_flags_none = 0;
/// The variable will not be loaded by ::load_all or saved by ::save_all, but it
/// has a key and can be loaded/saved manually.
k_no_auto_load = (1 << 0),
/// The variable will not be loaded by ::load_all or saved by ::save_all, but it
/// has a key and can be loaded/saved manually.
static const Flags k_flag_no_auto_load = (1 << 0);
/// This flag is advisory; it indicates that the variable's value should not be
/// imported from outside, e.g. from a GCS.
k_no_import = (1 << 1)
};
/// This flag is advisory; it indicates that the variable's value should not be
/// imported from outside, e.g. from a GCS.
static const Flags k_flag_no_import = (1 << 1);
/// Constructor
/// This flag indicates that the variable is really a group; it is normally
/// set automatically by the AP_Var_group constructor.
///
static const Flags k_flag_is_group = (1 << 2);
/// This flag indicates that the variable wants to opt out of being listed.
///
static const Flags k_flag_unlisted = (1 << 3);
/// Constructor for a freestanding variable
///
/// @param key The storage key to be associated with this variable.
/// @param name An optional name by which the variable may be known.
/// This name may be looked up via the ::lookup function.
/// @param group An optional group to which the variable may belong.
/// The scope's name will be prepended to the variable name
/// by ::copy_name.
/// @param flags Optional flags which control how the variable behaves.
///
AP_Var(Key key = k_no_key, const prog_char *name = NULL, AP_Var_group *group = NULL, Flags flags = k_no_flags);
AP_Var(Key key = k_key_none, const prog_char *name = NULL, Flags flags = k_flags_none);
/// Constructor for variable belonging to a group
///
/// @param group The group the variable belongs to.
/// @param index The position of the variable in the group.
/// @param name An optional name by which the variable may be known.
/// @param flags Optional flags which control how the variable behaves.
///
AP_Var(AP_Var_group *group, Key index, const prog_char *name, Flags flags = k_flags_none);
/// Destructor
///
/// 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
/// 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.
/// For freestanding variables, this will remove the variable from the global list
/// of variables. The list is organised FIFO, so locally-constructed freestanding
/// variables are typically cheap to destroy as they tend to be at or very close to
/// the head of the list.
///
/// Destroying a variable that is a group member may be less efficient as the list
/// of variables that are group members is sorted by key, requiring a traversal
/// of the list up to the index before it can be removed.
///
/// Destroying a group removes all variables that are members of the group from
/// the list, requiring a complete traversal of the list of group-member variables.
/// If the group is destroyed before its members, they will also traverse the entire
/// list as they attempt to remove themselves.
///
/// The moral of the story: be careful when creating groups with local scope.
///
~AP_Var(void);
/// Copy the variable's name, prefixed by any parent class names, to a buffer.
/// Copy the variable's name, prefixed by any containing group name, to a buffer.
///
/// If the variable has no name, the buffer will contain an empty string.
///
@ -162,21 +195,6 @@ public:
///
void copy_name(char *buffer, size_t bufferSize) const;
/// Return a pointer to the n'th known variable.
///
/// This function is used to iterate the set of variables, and is optimised
/// for the case where the index argument is increased sequentially from one
/// call to the next.
///
/// Note that variable index numbers are not constant; they will vary
/// from build to build.
///
/// @param index Enumerator for the variable to be returned
/// @return Pointer to the index'th variable, or NULL if
/// the set of variables has been exhausted.
///
static AP_Var *lookup_by_index(int index);
/// Save the current value of the variable to EEPROM.
///
/// This interface works for any subclass that implements
@ -226,6 +244,16 @@ public:
///
static bool load_all(void);
/// Erase all variables in EEPROM.
///
/// This can be used prior to save_all to ensure that only known variables
/// will be present in the EEPROM.
///
/// It can also be used immediately prior to reset, followed by a save_all,
/// to restore all saved variables to their initial value.
///
static void erase_all(void);
/// Test for flags that may be set.
///
/// @param flagval Flag or flags to be tested
@ -241,26 +269,63 @@ public:
///
AP_Var_group *group(void) { return _group; }
/// Returns the next variable in the global list
/// Returns the first variable in the global list.
///
/// @return The first variable in the global list, or NULL if
/// there are none.
///
static AP_Var *first(void) { return _variables; }
/// Returns the next variable in the global list.
///
/// All standalone variables are returned first, then all grouped variables.
/// Note that groups themselves are considered standalone variables.
///
/// A caller not wishing to iterate grouped variables should test the return
/// value from this function with ::group, and if non-null, ignore it.
///
/// XXX how to ignore groups?
///
/// @return The next variable, either the next group member in order or
/// the next variable in an arbitrary order, or NULL if this is
/// the last variable in the list.
///
AP_Var *next(void) { return _link; }
AP_Var *next(void);
/// Returns the first variable that is a member of a specific group.
///
/// @param group The group whose member(s) are sought.
/// @return The first variable in the group, or NULL if there are none.
///
static AP_Var *first_member(AP_Var_group *group);
/// Returns the next variable that is a member of the same group.
///
/// This does not behave correctly if called on a variable that is not a group member.
///
/// @param group The group whose member(s) are sought.
/// @return The next variable in the group, or NULL if there are none.
///
AP_Var *next_member();
/// Returns the storage key for a variable.
///
/// Note that group members do not have storage keys - the key is held by the group.
///
/// @return The variable's key, or k_key_none if it does not have a key.
///
Key key(void);
private:
AP_Var_group *_group; ///< Group that the variable may be a member of
AP_Var *_link; ///< linked list pointer to next variable
Key _key; ///< storage key
Key _key; ///< Storage key; see the discussion of Key above.
const prog_char *_name; ///< name known to external agents (GCS, etc.)
uint8_t _flags; ///< flag bits
// static state used by ::lookup
static AP_Var *_variables; ///< linked list of all variables
static AP_Var *_lookup_hint; ///< pointer to the last variable that was looked up by ::lookup
static int _lookup_hint_index; ///< index of the last variable that was looked up by ::lookup
static AP_Var *_variables; ///< linked list of all freestanding variables
static AP_Var *_grouped_variables; ///< linked list of all grouped variables
// EEPROM space allocation and scanning
static uint16_t _tail_sentinel; ///< EEPROM address of the tail sentinel
@ -269,20 +334,6 @@ private:
static const uint16_t k_EEPROM_size = 4096; ///< XXX avr-libc doesn't consistently export this
/// Return a pointer to the variable with a given key.
///
/// This function is used to search the set of variables for
/// one with a given key.
///
/// Note that this search will fail (XXX should it?) if the variable
/// assigned this key has been located in EEPROM.
///
/// @param key The key to search for.
/// @return Pointer to the variable assigned the key,
/// or NULL if no variable owns up to it.
///
static AP_Var *_lookup_by_key(Key key);
/// Scan the EEPROM and assign addresses to any known variables
/// that have entries there.
///
@ -325,8 +376,8 @@ public:
/// @param key Storage key for the group.
/// @param name An optional name prefix for members of the group.
///
AP_Var_group(Key key = k_no_key, const prog_char *name = NULL) :
AP_Var(key, name, NULL, k_no_flags)
AP_Var_group(Key key = k_key_none, const prog_char *name = NULL, Flags flags = k_flags_none) :
AP_Var(key, name, flags | k_flag_is_group)
{
}
@ -368,7 +419,6 @@ private:
///
size_t _serialize_unserialize(void *buf, size_t buf_size, bool do_serialize);
};
/// Template class for scalar variables.
@ -387,16 +437,16 @@ public:
/// Initialises a stand-alone variable with optional initial value, storage key, name and flags.
///
/// @param default_value Value the variable should have at startup.
/// @param key Storage key for the variable. If not set, or set to AP_Var::k_no_key
/// @param key Storage key for the variable. If not set, or set to AP_Var::k_key_none
/// the variable cannot be loaded from or saved to EEPROM.
/// @param name An optional name by which the variable may be known.
/// @param flags Optional flags that may affect the behaviour of the variable.
///
AP_VarT<T> (T initial_value = 0,
Key key = k_no_key,
Key key = k_key_none,
const prog_char *name = NULL,
Flags flags = k_no_flags) :
AP_Var(key, name, NULL, flags),
Flags flags = k_flags_none) :
AP_Var(key, name, flags),
_value(initial_value)
{
}
@ -417,8 +467,8 @@ public:
Key index,
T initial_value,
const prog_char *name = NULL,
Flags flags = k_no_flags) :
AP_Var(index, name, group, flags),
Flags flags = k_flags_none) :
AP_Var(group, index, name, flags),
_value(initial_value)
{
}
@ -507,9 +557,9 @@ public:
/// Constructors mimic AP_Float::AP_Float()
///
AP_Float16(float initial_value = 0,
Key key = k_no_key,
Key key = k_key_none,
const prog_char *name = NULL,
Flags flags = k_no_flags) :
Flags flags = k_flags_none) :
AP_Float(initial_value, key, name, flags)
{
}
@ -518,7 +568,7 @@ public:
Key index,
float initial_value = 0,
const prog_char *name = NULL,
Flags flags = k_no_flags) :
Flags flags = k_flags_none) :
AP_Float(group, index, initial_value, name, flags)
{
}

View File

@ -17,27 +17,10 @@ FastSerialPort(Serial, 0);
class Test
{
public:
Test(const char *name) : _name(name), _fail(false) {}
~Test() {
Serial.printf("%s: %s\n", _fail ? "FAILED" : "passed", _name);
if (_fail) {
_failed++;
} else {
_passed++;
}
}
void require(bool expr, const char *source) {
if (!expr) {
_fail = true;
Serial.printf("%s: fail: %s\n", _name, source);
}
}
static void report() {
Serial.printf("\n%d passed %d failed\n", _passed, _failed);
}
Test(const char *name);
~Test();
void require(bool expr, const char *source);
static void report();
private:
const char *_name;
@ -46,6 +29,37 @@ private:
static int _failed;
};
Test::Test(const char *name) :
_name(name),
_fail(false)
{
}
Test::~Test()
{
Serial.printf("%s: %s\n", _fail ? "FAILED" : "passed", _name);
if (_fail) {
_failed++;
} else {
_passed++;
}
}
void
Test::require(bool expr, const char *source)
{
if (!expr) {
_fail = true;
Serial.printf("%s: fail: %s\n", _name, source);
}
}
void
Test::report()
{
Serial.printf("\n%d passed %d failed\n", _passed, _failed);
}
int Test::_passed = 0;
int Test::_failed = 0;
@ -58,7 +72,8 @@ int Test::_failed = 0;
void
setup(void)
{
Serial.begin(38400);
Serial.begin(115200);
Serial.println("AP_Var unit tests.\n");
// MetaClass: test type ID
{
@ -71,19 +86,28 @@ setup(void)
uint16_t m1 = f1.meta_type_id();
uint16_t m2 = f2.meta_type_id();
uint16_t m3 = i1.meta_type_id();
uint16_t m4 = AP_Meta_class::meta_type_id<AP_Float>();
REQUIRE(m1 != 0);
REQUIRE(m1 == m2);
REQUIRE(m1 != m3);
REQUIRE(AP_Meta_class::meta_type_equivalent(&f1, &f2));
REQUIRE(!AP_Meta_class::meta_type_equivalent(&f1, &i1));
REQUIRE(NULL != AP_Meta_class::meta_cast<AP_Float>(&f1));
REQUIRE(NULL == AP_Meta_class::meta_cast<AP_Int8>(&f1));
REQUIRE(NULL == AP_Meta_class::meta_cast<AP_Float16>(&f1));
REQUIRE(m1 == m4);
}
// MetaClass: test external handles
// MetaClass: meta_type_equivalent
{
TEST(meta_type_equivalent);
AP_Float f1;
AP_Float f2;
AP_Int8 i1;
REQUIRE(AP_Meta_class::meta_type_equivalent(&f1, &f2));
REQUIRE(!AP_Meta_class::meta_type_equivalent(&f1, &i1));
}
// MetaClass: external handles
{
TEST(meta_handle);
@ -120,9 +144,11 @@ setup(void)
{
TEST(var_initial_value);
AP_Float f(12.345);
AP_Float f1(12.345);
AP_Float f2;
REQUIRE(f == 12.345);
REQUIRE(f1 == 12.345);
REQUIRE(f2 == 0);
}
// AP_Var: set, get, assignment
@ -169,7 +195,7 @@ setup(void)
{
TEST(var_naming);
AP_Float f(0, AP_Var::k_no_key, PSTR("test"));
AP_Float f(0, AP_Var::k_key_none, PSTR("test"));
char name_buffer[16];
f.copy_name(name_buffer, sizeof(name_buffer));
@ -203,6 +229,53 @@ setup(void)
REQUIRE(f == 10);
}
// AP_Var: groups and names
{
TEST(group_names);
AP_Var_group group(AP_Var::k_key_none, PSTR("group_"));
AP_Float f(&group, 1, 1.0, PSTR("test"));
char name_buffer[16];
f.copy_name(name_buffer, sizeof(name_buffer));
REQUIRE(!strcmp(name_buffer, "group_test"));
}
// AP_Var: enumeration
{
TEST(empty_variables);
REQUIRE(AP_Var::first() == NULL);
}
{
TEST(enumerate_variables);
AP_Float f1;
REQUIRE(AP_Var::first() == &f1);
{
AP_Var_group group;
AP_Var f2(&group, 0, 0);
AP_Var f3(&group, 1, 0);
AP_Var *vp;
vp = AP_Var::first();
REQUIRE(vp == &group); // XXX presumes FIFO insertion
vp = vp->next();
REQUIRE(vp == &f1); // XXX presumes FIFO insertion
vp = vp->next();
REQUIRE(vp == &f2); // first variable in the grouped list
vp = AP_Var::first_member(&group);
REQUIRE(vp == &f2);
vp = vp->next_member();
REQUIRE(vp == &f3);
}
}
#if 0
// AP_Var: enumeration
// note that this test presumes the singly-linked list implementation of the list
{
@ -211,19 +284,19 @@ setup(void)
AP_Var *v = AP_Var::lookup_by_index(0);
// test basic enumeration
AP_Float f1(0, AP_Var::k_no_key, PSTR("test1"));
AP_Float f1(0, AP_Var::k_key_none, PSTR("test1"));
REQUIRE(AP_Var::lookup_by_index(0) == &f1);
REQUIRE(AP_Var::lookup_by_index(1) == v);
// test that new entries arrive in order
{
AP_Float f2(0, AP_Var::k_no_key, PSTR("test2"));
AP_Float f2(0, AP_Var::k_key_none, PSTR("test2"));
REQUIRE(AP_Var::lookup_by_index(0) == &f2);
REQUIRE(AP_Var::lookup_by_index(1) == &f1);
REQUIRE(AP_Var::lookup_by_index(2) == v);
{
AP_Float f3(0, AP_Var::k_no_key, PSTR("test3"));
AP_Float f3(0, AP_Var::k_key_none, PSTR("test3"));
REQUIRE(AP_Var::lookup_by_index(0) == &f3);
REQUIRE(AP_Var::lookup_by_index(1) == &f2);
REQUIRE(AP_Var::lookup_by_index(2) == &f1);
@ -235,18 +308,7 @@ setup(void)
REQUIRE(AP_Var::lookup_by_index(0) == &f1);
REQUIRE(AP_Var::lookup_by_index(1) == v);
}
// AP_Var: group names
{
TEST(group_names);
AP_Var_group group(AP_Var::k_no_key, PSTR("group_"));
AP_Float f(&group, 1, 1.0, PSTR("test"));
char name_buffer[16];
f.copy_name(name_buffer, sizeof(name_buffer));
REQUIRE(!strcmp(name_buffer, "group_test"));
}
#endif
#if SAVE
// AP_Var: load and save
@ -285,7 +347,6 @@ setup(void)
f1.load();
REQUIRE(f1 == 1);
}
#endif
// AP_Var: derived types
{
@ -299,7 +360,7 @@ setup(void)
f.load();
REQUIRE(f = 10.0);
}
#endif
Test::report();
}