Formatting and naming changes for conformance with the ArduPilot Coding Conventions.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1502 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok@gmail.com 2011-01-16 09:14:21 +00:00
parent 610e26db36
commit 96d2dc33fe
5 changed files with 793 additions and 790 deletions

View File

@ -1,4 +1,4 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// //
// This is free software; you can redistribute it and/or modify it under // This is free software; you can redistribute it and/or modify it under
// the terms of the GNU Lesser General Public License as published by the // the terms of the GNU Lesser General Public License as published by the
@ -14,25 +14,23 @@
#include "AP_MetaClass.h" #include "AP_MetaClass.h"
// Default ctor, currently does nothing // Default ctor, currently does nothing
AP_MetaClass::AP_MetaClass(void) AP_Meta_class::AP_Meta_class(void)
{ {
} }
// Default dtor, currently does nothing but must be defined in order to ensure that // Default dtor, currently does nothing but must be defined in order to ensure that
// subclasses not overloading the default virtual dtor still have something in their // subclasses not overloading the default virtual dtor still have something in their
// vtable. // vtable.
AP_MetaClass::~AP_MetaClass() AP_Meta_class::~AP_Meta_class()
{ {
} }
size_t size_t AP_Meta_class::serialize(void *buf, size_t bufSize) const
AP_MetaClass::serialize(void *buf, size_t bufSize) const
{ {
return 0; return 0;
} }
size_t size_t AP_Meta_class::unserialize(void *buf, size_t bufSize)
AP_MetaClass::unserialize(void *buf, size_t bufSize)
{ {
return 0; return 0;
} }

View File

@ -1,4 +1,4 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// //
// This is free software; you can redistribute it and/or modify it under // This is free software; you can redistribute it and/or modify it under
// the terms of the GNU Lesser General Public License as published by the // the terms of the GNU Lesser General Public License as published by the
@ -6,7 +6,7 @@
// your option) any later version. // your option) any later version.
// //
/// @file AP_MetaClass.h /// @file AP_Meta_class.h
/// @brief An abstract base class from which other classes can inherit. /// @brief An abstract base class from which other classes can inherit.
/// ///
/// This abstract base class declares and implements functions that are /// This abstract base class declares and implements functions that are
@ -17,215 +17,217 @@
/// basic functions. /// basic functions.
/// ///
#ifndef AP_METACLASS_H #ifndef AP_META_CLASS_H
#define AP_METACLASS_H #define AP_META_CLASS_H
#include <stddef.h> // for size_t #include <stddef.h> // for size_t
#include <inttypes.h> #include <inttypes.h>
#include <avr/io.h> // for RAMEND #include <avr/io.h> // for RAMEND
/// Basic meta-class from which other AP_* classes can derive. /// Basic meta-class from which other AP_* classes can derive.
/// ///
/// Functions that form the public API to the metaclass are prefixed meta_. /// Functions that form the public API to the metaclass are prefixed meta_.
/// ///
class AP_MetaClass class AP_Meta_class
{ {
public: public:
/// Default constructor does nothing. /// Default constructor does nothing.
AP_MetaClass(void); AP_Meta_class(void);
/// Default destructor is virtual, to ensure that all subclasses' /// Default destructor is virtual, to ensure that all subclasses'
/// destructors are virtual. This guarantees that all destructors /// destructors are virtual. This guarantees that all destructors
/// in the inheritance chain are called at destruction time. /// in the inheritance chain are called at destruction time.
/// ///
virtual ~AP_MetaClass(); virtual ~AP_Meta_class();
/// Typedef for the ID unique to all instances of a class. /// Typedef for the ID unique to all instances of a class.
/// ///
/// See ::meta_type_id for a discussion of class type IDs. /// See ::meta_type_id for a discussion of class type IDs.
/// ///
typedef uint16_t AP_TypeID; typedef uint16_t AP_Type_id;
/// Obtain a value unique to all instances of a specific subclass. /// Obtain a value unique to all instances of a specific subclass.
/// ///
/// The value can be used to determine whether two class pointers /// The value can be used to determine whether two class pointers
/// refer to the same exact class type. The value can also be cached /// refer to the same exact class type. The value can also be cached
/// and then used to detect objects of a given type at a later point. /// and then used to detect objects of a given type at a later point.
/// ///
/// This is similar to the basic functionality of the C++ typeid /// This is similar to the basic functionality of the C++ typeid
/// keyword, but does not depend on std::type_info or any compiler- /// keyword, but does not depend on std::type_info or any compiler-
/// generated RTTI. /// generated RTTI.
/// ///
/// The value is derived from the vtable address, so it is guaranteed /// The value is derived from the vtable address, so it is guaranteed
/// to be unique but cannot be known until the program has been compiled /// to be unique but cannot be known until the program has been compiled
/// and linked. Thus, the only way to know the type ID of a given /// and linked. Thus, the only way to know the type ID of a given
/// type is to construct an object at runtime. To cache the type ID /// type is to construct an object at runtime. To cache the type ID
/// of a class Foo, one would write: /// of a class Foo, one would write:
/// ///
/// AP_MetaClass::AP_TypeID Foo_type_id; /// AP_Meta_class::AP_Type_id Foo_type_id;
/// ///
/// { Foo a; Foo_type_id = a.meta_type_id(); } /// { Foo a; Foo_type_id = a.meta_type_id(); }
/// ///
/// This will construct a temporary Foo object a and save its type ID. /// This will construct a temporary Foo object a and save its type ID.
/// ///
/// @param p A pointer to an instance of a subclass of AP_MetaClass. /// @param p A pointer to an instance of a subclass of AP_Meta_class.
/// @return A type-unique value. /// @return A type-unique value.
/// ///
AP_TypeID meta_type_id(void) const { AP_Type_id meta_type_id(void) const {
return *(AP_TypeID *)this; return *(AP_Type_id *)this;
} }
/// External handle for an instance of an AP_MetaClass subclass, contains /// External handle for an instance of an AP_Meta_class subclass, contains
/// enough information to construct and validate a pointer to the instance /// enough information to construct and validate a pointer to the instance
/// when passed back from an untrusted source. /// when passed back from an untrusted source.
/// ///
/// Handles are useful when passing a reference to an object to a client outside /// Handles are useful when passing a reference to an object to a client outside
/// the system, as they can be validated by the system when the client hands /// the system, as they can be validated by the system when the client hands
/// them back. /// them back.
/// ///
typedef uint32_t AP_MetaHandle; typedef uint32_t Meta_handle;
/// Return a value that can be used as an external pointer to an instance /// Return a value that can be used as an external pointer to an instance
/// of a subclass. /// of a subclass.
/// ///
/// The value can be passed to an untrusted agent, and validated on its return. /// The value can be passed to an untrusted agent, and validated on its return.
/// ///
/// The value contains the 16-bit type ID of the actual class and /// The value contains the 16-bit type ID of the actual class and
/// a pointer to the class instance. /// a pointer to the class instance.
/// ///
/// @return An opaque handle /// @return An opaque handle
/// ///
AP_MetaHandle meta_get_handle(void) const { Meta_handle meta_get_handle(void) const {
return ((AP_MetaHandle)meta_type_id() << 16) | (uint16_t)this; return ((Meta_handle)meta_type_id() << 16) | (uint16_t)this;
} }
/// Validates an AP_MetaClass handle. /// Validates an AP_Meta_class handle.
/// ///
/// The value of the handle is not required to be valid; in particular the /// The value of the handle is not required to be valid; in particular the
/// pointer encoded in the handle is validated before being dereferenced. /// pointer encoded in the handle is validated before being dereferenced.
/// ///
/// The handle is considered good if the pointer is valid and the object /// The handle is considered good if the pointer is valid and the object
/// it points to has a type ID that matches the ID in the handle. /// it points to has a type ID that matches the ID in the handle.
/// ///
/// @param handle A possible AP_MetaClass handle /// @param handle A possible AP_Meta_class handle
/// @return The instance pointer if the handle is good, /// @return The instance pointer if the handle is good,
/// or NULL if it is bad. /// or NULL if it is bad.
/// ///
static AP_MetaClass *meta_validate_handle(AP_MetaHandle handle) { static AP_Meta_class *meta_validate_handle(Meta_handle handle) {
AP_MetaClass *candidate = (AP_MetaClass *)(handle & 0xffff); // extract object pointer AP_Meta_class *candidate = (AP_Meta_class *)(handle & 0xffff); // extract object pointer
uint16_t id = handle >> 16; // and claimed type uint16_t id = handle >> 16; // and claimed type
// Sanity-check the pointer to ensure it lies within the device RAM, so that // Sanity-check the pointer to ensure it lies within the device RAM, so that
// a bad handle won't cause ::meta_type_id to read outside of SRAM. // a bad handle won't cause ::meta_type_id to read outside of SRAM.
// Assume that RAM (or addressable storage of some sort, at least) starts at zero. // Assume that RAM (or addressable storage of some sort, at least) starts at zero.
// //
// Note that this implies that we cannot deal with objects in ROM or EEPROM, // Note that this implies that we cannot deal with objects in ROM or EEPROM,
// but the constructor wouldn't be able to populate a vtable pointer there anyway... // but the constructor wouldn't be able to populate a vtable pointer there anyway...
// //
if ((uint16_t)candidate >= (RAMEND - 2)) // -2 to account for the type_id if ((uint16_t)candidate >= (RAMEND - 2)) { // -2 to account for the type_id
return NULL; return NULL;
}
// Compare the typeid of the object that candidate points to with the typeid // Compare the typeid of the object that candidate points to with the typeid
// from the handle. Note that it's safe to call meta_type_id() off the untrusted // from the handle. Note that it's safe to call meta_type_id() off the untrusted
// candidate pointer because meta_type_id is non-virtual (and will in fact be // candidate pointer because meta_type_id is non-virtual (and will in fact be
// inlined here). // inlined here).
// //
if (candidate->meta_type_id() == id) if (candidate->meta_type_id() == id) {
return candidate; return candidate;
}
return NULL; return NULL;
} }
/// Tests whether two objects are of precisely the same class. /// Tests whether two objects are of precisely the same class.
/// ///
/// Note that in the case where p2 inherits from p1, or vice-versa, this will return /// Note that in the case where p2 inherits from p1, or vice-versa, this will return
/// false as we cannot detect these inheritance relationships at runtime. /// false as we cannot detect these inheritance relationships at runtime.
/// ///
/// In the caller's context, p1 and p2 may be pointers to any type, but we require /// In the caller's context, p1 and p2 may be pointers to any type, but we require
/// that they be passed as pointers to AP_MetaClass in order to make it clear that /// that they be passed as pointers to AP_Meta_class in order to make it clear that
/// they should be pointers to classes derived from AP_MetaClass. /// they should be pointers to classes derived from AP_Meta_class.
/// ///
/// No attempt is made to validate whether p1 and p2 are actually derived from /// No attempt is made to validate whether p1 and p2 are actually derived from
/// AP_MetaClass. If p1 and p2 are equal, or if they point to non-class objects with /// AP_Meta_class. If p1 and p2 are equal, or if they point to non-class objects with
/// similar contents, or to non-AP_MetaClass derived classes with no virtual functions /// similar contents, or to non-AP_Meta_class derived classes with no virtual functions
/// this function may return true. /// this function may return true.
/// ///
/// @param p1 The first object to be compared. /// @param p1 The first object to be compared.
/// @param p2 The second object to be compared. /// @param p2 The second object to be compared.
/// @return True if the two objects are of the same class, false /// @return True if the two objects are of the same class, false
/// if they are not. /// if they are not.
/// ///
static bool meta_type_equivalent(AP_MetaClass *p1, AP_MetaClass *p2) { static bool meta_type_equivalent(AP_Meta_class *p1, AP_Meta_class *p2) {
return p1->meta_type_id() == p2->meta_type_id(); return p1->meta_type_id() == p2->meta_type_id();
} }
/// Cast a pointer to an expected class type. /// Cast a pointer to an expected class type.
/// ///
/// This function is used when a pointer is expected to be a pointer to a /// This function is used when a pointer is expected to be a pointer to a
/// subclass of AP_MetaClass, but the caller is not certain. It will return the pointer /// subclass of AP_Meta_class, but the caller is not certain. It will return the pointer
/// if it is, or NULL if it is not a pointer to the expected class. /// if it is, or NULL if it is not a pointer to the expected class.
/// ///
/// This should be used with caution, as _typename's default constructor and /// This should be used with caution, as _typename's default constructor and
/// destructor will be run, possibly introducing undesired side-effects. /// destructor will be run, possibly introducing undesired side-effects.
/// ///
/// @todo Consider whether we should make it difficult to have a default constructor /// @todo Consider whether we should make it difficult to have a default constructor
/// with appreciable side-effects. /// with appreciable side-effects.
/// ///
/// @todo Check whether we need to reinterpret_cast to get the right return type. /// @todo Check whether we need to reinterpret_cast to get the right return type.
/// ///
/// @param _p An AP_MetaClass subclass whose type is to be tested. /// @param _p An AP_Meta_class subclass whose type is to be tested.
/// @param _typename The name of a type with which _p is to be compared. /// @param _typename The name of a type with which _p is to be compared.
/// @return True if _p is of type _typename, false otherwise. /// @return True if _p is of type _typename, false otherwise.
/// ///
template<typename T> template<typename T>
static T* meta_cast(AP_MetaClass *p) { static T *meta_cast(AP_Meta_class *p) {
T tmp; T tmp;
if (meta_type_equivalent(p, &tmp)) if (meta_type_equivalent(p, &tmp)) {
return (T *)p; return (T *)p;
return NULL; }
} return NULL;
}
/// Serialize the class. /// Serialize the class.
/// ///
/// Serialization stores the state of the class in an external buffer in such a /// Serialization stores the state of the class in an external buffer in such a
/// fashion that it can later be restored by unserialization. /// fashion that it can later be restored by unserialization.
/// ///
/// AP_MetaClass subclasses should only implement these functions if saving and /// AP_Meta_class subclasses should only implement these functions if saving and
/// restoring their state makes sense. /// restoring their state makes sense.
/// ///
/// Serialization provides a mechanism for exporting the state of the class to an /// Serialization provides a mechanism for exporting the state of the class to an
/// external consumer, either for external introspection or for subsequent restoration. /// external consumer, either for external introspection or for subsequent restoration.
/// ///
/// Classes that wrap variables should define the format of their serialiaed data /// Classes that wrap variables should define the format of their serialiaed data
/// so that external consumers can reliably interpret it. /// so that external consumers can reliably interpret it.
/// ///
/// @param buf Buffer into which serialised data should be placed. /// @param buf Buffer into which serialised data should be placed.
/// @param bufSize The size of the buffer provided. /// @param bufSize The size of the buffer provided.
/// @return The size of the serialised data, even if that data would /// @return The size of the serialised data, even if that data would
/// have overflowed the buffer. If the return value is zero, /// have overflowed the buffer. If the return value is zero,
/// the class does not support serialization. /// the class does not support serialization.
/// ///
virtual size_t serialize(void *buf, size_t bufSize) const; virtual size_t serialize(void *buf, size_t bufSize) const;
/// Unserialize the class. /// Unserialize the class.
/// ///
/// Unserializing a class from a buffer into which the class previously serialized /// Unserializing a class from a buffer into which the class previously serialized
/// itself restores the instance to an identical state, where "identical" is left /// itself restores the instance to an identical state, where "identical" is left
/// up to the class itself to define. /// up to the class itself to define.
/// ///
/// Classes that wrap variables should define the format of their serialized data so /// Classes that wrap variables should define the format of their serialized data so
/// that external providers can reliably encode it. /// that external providers can reliably encode it.
/// ///
/// @param buf Buffer containing serialized data. /// @param buf Buffer containing serialized data.
/// @param bufSize The size of the buffer. /// @param bufSize The size of the buffer.
/// @return The number of bytes from the buffer that would be consumed /// @return The number of bytes from the buffer that would be consumed
/// unserializing the data. If the value is less than or equal /// unserializing the data. If the value is less than or equal
/// to bufSize, unserialization was successful. If the return /// to bufSize, unserialization was successful. If the return
/// value is zero the class does not support unserialisation or /// value is zero the class does not support unserialisation or
/// the data in the buffer is invalid. /// the data in the buffer is invalid.
/// ///
virtual size_t unserialize(void *buf, size_t bufSize); virtual size_t unserialize(void *buf, size_t bufSize);
}; };
#endif // AP_METACLASS_H #endif // AP_Meta_class_H

View File

@ -1,4 +1,4 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// //
// This is free software; you can redistribute it and/or modify it under // This is free software; you can redistribute it and/or modify it under
// the terms of the GNU Lesser General Public License as published by the // the terms of the GNU Lesser General Public License as published by the
@ -13,27 +13,28 @@
// Global constants exported // Global constants exported
// //
AP_Float AP_FloatUnity(1.0); AP_Float AP_Float_unity(1.0);
AP_Float AP_FloatNegativeUnity(-1.0); AP_Float AP_Float_negative_unity(-1.0);
AP_Float AP_FloatZero(0); AP_Float AP_Float_zero(0);
// 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;
// Constructor // Constructor
// //
AP_Var::AP_Var(AP_VarAddress address, AP_Var::AP_Var(Address address, const prog_char *name, const AP_Var_scope *scope, Flags flags) :
const prog_char *name, _address(address), _name(name), _scope(scope), _flags(flags)
const AP_VarScope *scope,
Flags flags) :
_address(address),
_name(name),
_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;
_variables = this; _variables = this;
// reset the lookup cache // reset the lookup cache
_lookupHintIndex = 0; _lookup_hint_index = 0;
} }
// Destructor // Destructor
@ -42,183 +43,178 @@ AP_Var::AP_Var(AP_VarAddress address,
// //
AP_Var::~AP_Var(void) AP_Var::~AP_Var(void)
{ {
// 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
AP_Var *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) {
// make it point at what we point at, and done // make it point at what we point at, and done
p->_link = _link; p->_link = _link;
break; break;
} }
// try the next one // try the next one
p = p->_link; p = p->_link;
} }
} }
// reset the lookup cache // reset the lookup cache
_lookupHintIndex = 0; _lookup_hint_index = 0;
} }
void void AP_Var::set_default(void)
AP_Var::set_default(void)
{ {
// Default implementation of ::set_default does nothing // Default implementation of ::set_default does nothing
} }
// Copy the variable name to the provided buffer. // Copy the variable name to the provided buffer.
// //
void void AP_Var::copy_name(char *buffer, size_t buffer_size) const
AP_Var::copy_name(char *buffer, size_t bufferSize) const
{ {
buffer[0] = '\0'; buffer[0] = '\0';
if (_scope) if (_scope) {
_scope->copy_name(buffer, bufferSize); _scope->copy_name(buffer, buffer_size);
strlcat_P(buffer, _name, bufferSize); }
strlcat_P(buffer, _name, buffer_size);
} }
// Compute any offsets that should be applied to a variable in this scope. // Compute any offsets that should be applied to a variable in this scope.
// //
// Note that this depends on the default _address value for scopes being zero. // Note that this depends on the default _address value for scopes being zero.
// //
AP_Var::AP_VarAddress AP_Var::Address AP_Var_scope::get_address(void) const
AP_VarScope::get_address(void) const
{ {
AP_Var::AP_VarAddress addr = _address; AP_Var::Address addr = _address;
if (_parent) if (_parent) {
addr += _parent->get_address(); addr += _parent->get_address();
}
return addr; return addr;
} }
// Compute the address in EEPROM where the variable is stored // Compute the address in EEPROM where the variable is stored
// //
AP_Var::AP_VarAddress AP_Var::Address AP_Var::_get_address(void) const
AP_Var::_get_address(void) const
{ {
AP_VarAddress addr = _address; Address addr = _address;
// if we have an address at all // if we have an address at all
if ((addr != AP_VarNoAddress) && _scope) if ((addr != k_no_address) && _scope) {
addr += _scope->get_address(); addr += _scope->get_address();
}
return addr; return addr;
} }
// Save the variable to EEPROM, if supported // Save the variable to EEPROM, if supported
// //
void void AP_Var::save(void) const
AP_Var::save(void) const
{ {
AP_VarAddress addr = _get_address(); Address addr = _get_address();
if (addr != AP_VarNoAddress) { if (addr != k_no_address) {
uint8_t vbuf[AP_VarMaxSize]; uint8_t vbuf[k_max_size];
size_t size; size_t size;
// serialize the variable into the buffer and work out how big it is // serialize the variable into the buffer and work out how big it is
size = serialize(vbuf, sizeof(vbuf)); size = serialize(vbuf, sizeof(vbuf));
// if it fit in the buffer, save it to EEPROM // if it fit in the buffer, save it to EEPROM
if (size <= sizeof(vbuf)) if (size <= sizeof(vbuf)) {
eeprom_write_block(vbuf, (void *)addr, size); eeprom_write_block(vbuf, (void *)addr, size);
} }
}
} }
// Load the variable from EEPROM, if supported // Load the variable from EEPROM, if supported
// //
void void AP_Var::load(void)
AP_Var::load(void)
{ {
AP_VarAddress addr = _get_address(); Address addr = _get_address();
if (addr != AP_VarNoAddress) { if (addr != k_no_address) {
uint8_t vbuf[AP_VarMaxSize]; uint8_t vbuf[k_max_size];
size_t size; size_t size;
// ask the unserializer how big the variable is // ask the unserializer how big the variable is
size = unserialize(NULL, 0); size = unserialize(NULL, 0);
// read the buffer from EEPROM // read the buffer from EEPROM
if (size <= sizeof(vbuf)) { if (size <= sizeof(vbuf)) {
eeprom_read_block(vbuf, (void *)addr, size); eeprom_read_block(vbuf, (void *)addr, size);
unserialize(vbuf, size); unserialize(vbuf, size);
} }
} }
} }
// //
// Lookup interface for variables. // Lookup interface for variables.
// //
AP_Var *AP_Var::_variables = NULL;
AP_Var *AP_Var::_lookupHint = NULL;
int AP_Var::_lookupHintIndex = 0;
AP_Var * AP_Var *
AP_Var::lookup(int index) AP_Var::lookup(int index)
{ {
AP_Var *p; AP_Var *p;
int i; int i;
// establish initial search state // establish initial search state
if (_lookupHintIndex && // we have a cached hint if (_lookup_hint_index && // we have a cached hint
(index >= _lookupHintIndex)) { // the desired index is at or after the hint (index >= _lookup_hint_index)) { // the desired index is at or after the hint
p = _lookupHint; // start at the hint point p = _lookup_hint; // start at the hint point
i = index - _lookupHintIndex; // count only the distance from the hint to the index i = index - _lookup_hint_index; // count only the distance from the hint to the index
} else { } else {
p = _variables; // start at the beginning of the list p = _variables; // start at the beginning of the list
i = index; // count to the index i = index; // count to the index
} }
// search // search
while (i-- && 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 = index; _lookup_hint_index = index;
_lookupHint = p; _lookup_hint = p;
} }
return(p); return (p);
} }
// Save all variables that have an identity. // Save all variables that have an identity.
// //
void void AP_Var::save_all(void)
AP_Var::save_all(void)
{ {
AP_Var *p = _variables; AP_Var *p = _variables;
while (p) { while (p) {
if (!p->has_flags(NO_AUTO_LOAD)) if (!p->has_flags(k_no_auto_load)) {
p->save(); p->save();
p = p->_link; }
} p = p->_link;
}
} }
// Load all variables that have an identity. // Load all variables that have an identity.
// //
void void AP_Var::load_all(void)
AP_Var::load_all(void)
{ {
AP_Var *p = _variables; AP_Var *p = _variables;
while (p) { while (p) {
if (!p->has_flags(NO_AUTO_LOAD)) if (!p->has_flags(k_no_auto_load)) {
p->load(); p->load();
p = p->_link; }
} p = p->_link;
}
} }

View File

@ -1,4 +1,4 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// //
// This is free software; you can redistribute it and/or modify it under // This is free software; you can redistribute it and/or modify it under
// the terms of the GNU Lesser General Public License as published by the // the terms of the GNU Lesser General Public License as published by the
@ -16,8 +16,8 @@
/// of variables to be passed to blocks for floating point /// of variables to be passed to blocks for floating point
/// math, memory management, etc. /// math, memory management, etc.
#ifndef AP_Var_H #ifndef AP_VAR_H
#define AP_Var_H #define AP_VAR_H
#include <stddef.h> #include <stddef.h>
#include <string.h> #include <string.h>
#include <stdint.h> #include <stdint.h>
@ -27,147 +27,147 @@
#include "AP_MetaClass.h" #include "AP_MetaClass.h"
class AP_VarScope; class AP_Var_scope;
/// Base class for variables. /// Base class for variables.
/// ///
/// Provides naming and lookup services for variables. /// Provides naming and lookup services for variables.
/// ///
class AP_Var : public AP_MetaClass class AP_Var : public AP_Meta_class
{ {
public: public:
/// Storage address for variables that can be saved to EEPROM /// Storage address for variables that can be saved to EEPROM
/// ///
/// If the variable is contained within a scope, then the address /// If the variable is contained within a scope, then the address
/// is relative to the scope. /// is relative to the scope.
/// ///
/// @todo This might be used as a token for mass serialisation, /// @todo This might be used as a token for mass serialisation,
/// but for now it's just the address of the variable's backing /// but for now it's just the address of the variable's backing
/// store in EEPROM. /// store in EEPROM.
/// ///
typedef uint16_t AP_VarAddress; typedef uint16_t Address;
/// An address value that indicates that a variable is not to be saved to EEPROM. /// An address 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 /// As the value has all bits set to 1, it's not a legal EEPROM address for any
/// EEPROM smaller than 64K. /// EEPROM smaller than 64K.
/// ///
/// This value is normally the default. /// This value is normally the default.
/// ///
static const AP_VarAddress AP_VarNoAddress = ~(AP_VarAddress)0; static const Address k_no_address = ~(Address)0;
/// The largest variable that will be saved to EEPROM. /// The largest variable that will be saved to EEPROM.
/// This affects the amount of stack space that is required by the ::save, ::load, /// This affects the amount of stack space that is required by the ::save, ::load,
/// ::save_all and ::load_all functions. /// ::save_all and ::load_all functions.
/// ///
static const size_t AP_VarMaxSize = 16; static const size_t k_max_size = 16;
/// Optional flags affecting the behavior and usage of the variable. /// Optional flags affecting the behavior and usage of the variable.
/// ///
enum Flags { enum Flags {
NO_FLAGS = 0, k_no_flags = 0,
NO_AUTO_LOAD = (1<<0), ///< will not be loaded by ::load_all or saved by ::save_all k_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 k_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.
/// This name may be looked up via the ::lookup function. /// This name may be looked up via the ::lookup function.
/// @param scope An optional scope that the variable may be a contained within. /// @param scope An optional scope that the variable may be a contained within.
/// The scope's name will be prepended to the variable name /// The scope's name will be prepended to the variable name
/// by ::copy_name. /// by ::copy_name.
/// ///
AP_Var(AP_VarAddress address = AP_VarNoAddress, AP_Var(Address address = k_no_address, const prog_char *name = NULL, const AP_Var_scope *scope = NULL,
const prog_char *name = NULL, Flags flags = k_no_flags);
const AP_VarScope *scope = NULL,
Flags flags = NO_FLAGS);
/// Destructor /// Destructor
/// ///
/// Note that the linked-list removal can be inefficient when 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. This is not a major issue for variables created /// they are created. This is not a major issue for variables created
/// and destroyed automatically at block boundaries, and the creation and /// and destroyed automatically at block boundaries, and the creation and
/// destruction of variables by hand is generally discouraged. /// destruction of variables by hand is generally discouraged.
/// ///
~AP_Var(void); ~AP_Var(void);
/// Set the variable to its default value /// Set the variable to its default value
/// ///
virtual void set_default(void); 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.
/// ///
/// Note that if the combination of names is larger than the buffer, the /// Note that if the combination of names is larger than the buffer, the
/// result in the buffer will be truncated. /// result in the buffer will be truncated.
/// ///
/// @param buffer The destination buffer /// @param buffer The destination buffer
/// @param bufferSize Total size of the destination buffer. /// @param bufferSize Total size of the destination buffer.
/// ///
void copy_name(char *buffer, size_t bufferSize) const; void copy_name(char *buffer, size_t bufferSize) const;
/// Return a pointer to the n'th known variable. /// Return a pointer to the n'th known variable.
/// ///
/// This function is used to iterate the set of variables that are considered /// This function is used to iterate the set of variables that are considered
/// interesting; i.e. those that may be saved to EEPROM, or that have a name. /// interesting; i.e. those that may be saved to EEPROM, or that have a name.
/// ///
/// Note that variable index numbers are not constant, they depend on the /// Note that variable index numbers are not constant, they depend on the
/// the static construction order. /// the static construction order.
/// ///
/// @param index enumerator for the variable to be returned /// @param index enumerator for the variable to be returned
/// ///
static AP_Var *lookup(int index); static AP_Var *lookup(int index);
/// Save the current value of the variable to EEPROM. /// Save the current value of the variable to EEPROM.
/// ///
/// This interface works for any subclass that implements /// This interface works for any subclass that implements
/// serialize. /// serialize.
/// ///
void save(void) const; void save(void) const;
/// Load the variable from EEPROM. /// Load the variable from EEPROM.
/// ///
/// This interface works for any subclass that implements /// This interface works for any subclass that implements
/// unserialize. /// unserialize.
/// ///
void load(void); void load(void);
/// Save all variables to EEPROM /// Save all variables to EEPROM
/// ///
static void save_all(void); static void save_all(void);
/// Load all variables from EEPROM /// Load all variables from EEPROM
/// ///
static void load_all(void); static void load_all(void);
/// Test for flags that may be set. /// Test for flags that may be set.
/// ///
/// @param flagval Flag or flags to be tested /// @param flagval Flag or flags to be tested
/// @returns True if all of the bits in flagval are set in the flags. /// @returns True if all of the bits in flagval are set in the flags.
/// ///
bool has_flags(Flags flagval) const { return (_flags & flagval) == flagval; } bool has_flags(Flags flagval) const {
return (_flags & flagval) == flagval;
}
private: private:
const AP_VarAddress _address; const Address _address;
const prog_char *_name; const prog_char *_name;
const AP_VarScope * const _scope; const AP_Var_scope *const _scope;
AP_Var *_link; AP_Var *_link;
uint8_t _flags; 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
/// ///
/// @returns The address at which the variable is stored in EEPROM, /// @returns The address at which the variable is stored in EEPROM,
/// or AP_VarNoAddress if it is not saved. /// or k_no_address if it is not saved.
/// ///
AP_VarAddress _get_address(void) const; Address _get_address(void) const;
// static state used by ::lookup // static state used by ::lookup
static AP_Var *_variables; static AP_Var *_variables;
static AP_Var *_lookupHint; /// pointer to the last variable that was looked up by ::lookup static AP_Var *_lookup_hint; /// pointer to the last variable that was looked up by ::lookup
static int _lookupHintIndex; /// index of 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
}; };
/// Nestable scopes for variable names. /// Nestable scopes for variable names.
@ -184,55 +184,49 @@ private:
/// into account the address offsets of each of the variable's /// into account the address offsets of each of the variable's
/// enclosing scopes. /// enclosing scopes.
/// ///
class AP_VarScope class AP_Var_scope
{ {
public: public:
/// Constructor /// Constructor
/// ///
/// @param name The name of the scope. /// @param name The name of the scope.
/// @param address An EEPROM address offset to be added to the address assigned to /// @param address An EEPROM address offset to be added to the address assigned to
/// any variables within the scope. /// any variables within the scope.
/// @param parent Optional parent scope to nest within. /// @param parent Optional parent scope to nest within.
/// ///
AP_VarScope(const prog_char *name, AP_Var_scope(const prog_char *name, AP_Var::Address address = 0, AP_Var_scope *parent = NULL) :
AP_Var::AP_VarAddress address = 0, _name(name), _parent(parent), _address(address) {
AP_VarScope *parent = NULL) : }
_name(name),
_parent(parent),
_address(address)
{
}
/// Copy the scope name, prefixed by any parent scope names, to a buffer. /// Copy the scope name, prefixed by any parent scope names, to a buffer.
/// ///
/// Note that if the combination of names is larger than the buffer, the /// Note that if the combination of names is larger than the buffer, the
/// result in the buffer will be truncated. /// result in the buffer will be truncated.
/// ///
/// @param buffer The destination buffer /// @param buffer The destination buffer
/// @param bufferSize Total size of the destination buffer. /// @param bufferSize Total size of the destination buffer.
/// ///
void copy_name(char *buffer, size_t bufferSize) const void copy_name(char *buffer, size_t bufferSize) const {
{ if (_parent) {
if (_parent) _parent->copy_name(buffer, bufferSize);
_parent->copy_name(buffer, bufferSize); }
strlcat_P(buffer, _name, bufferSize); strlcat_P(buffer, _name, bufferSize);
} }
/// Compute the address offset that this and any parent scope might apply /// Compute the address offset that this and any parent scope might apply
/// to variables inside the scope. /// to variables inside the scope.
/// ///
/// This provides a way for variables to be grouped into collections whose /// This provides a way for variables to be grouped into collections whose
/// EEPROM addresses can be more easily managed. /// EEPROM addresses can be more easily managed.
/// ///
AP_Var::AP_VarAddress get_address(void) const; AP_Var::Address get_address(void) const;
private: private:
const prog_char *_name; /// pointer to the scope name in program memory const prog_char *_name; /// pointer to the scope name in program memory
AP_VarScope *_parent; /// pointer to a parent scope, if one exists AP_Var_scope *_parent; /// pointer to a parent scope, if one exists
AP_Var::AP_VarAddress _address; /// container base address, offsets contents AP_Var::Address _address; /// container base address, offsets contents
}; };
/// Template class for scalar variables. /// Template class for scalar variables.
/// ///
/// Objects of this type have a value, and can be treated in many ways as though they /// Objects of this type have a value, and can be treated in many ways as though they
@ -244,86 +238,91 @@ template<typename T>
class AP_VarT : public AP_Var class AP_VarT : public AP_Var
{ {
public: public:
/// Constructor /// Constructor
/// ///
/// @note Constructors for AP_Var are specialised so that they can /// @note Constructors for AP_Var are specialised so that they can
/// pass the correct typeCode argument to the AP_Var ctor. /// pass the correct typeCode argument to the AP_Var ctor.
/// ///
/// @param initialValue Value the variable should have at startup. /// @param initialValue Value the variable should have at startup.
/// @param identity A unique token used when saving the variable to EEPROM. /// @param identity A unique token used when saving the variable to EEPROM.
/// Note that this token must be unique, and should only be /// Note that this token must be unique, and should only be
/// changed for a variable if the EEPROM version is updated /// changed for a variable if the EEPROM version is updated
/// to prevent the accidental unserialisation of old data /// to prevent the accidental unserialisation of old data
/// into the wrong variable. /// into the wrong variable.
/// @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 defaultValue = 0, AP_VarT<T> (T default_value = 0, Address address = k_no_address, const prog_char *name = NULL,
AP_VarAddress address = AP_VarNoAddress, AP_Var_scope *scope = NULL, Flags flags = k_no_flags) :
const prog_char *name = NULL, AP_Var(address, name, scope, flags), _value(default_value), _default_value(default_value) {
AP_VarScope *scope = NULL, }
Flags flags = NO_FLAGS) :
AP_Var(address, name, scope, flags),
_value(defaultValue),
_defaultValue(defaultValue)
{
}
// serialize _value into the buffer, but only if it is big enough. // serialize _value into the buffer, but only if it is big enough.
// //
virtual size_t serialize(void *buf, size_t size) const { virtual size_t serialize(void *buf, size_t size) const {
if (size >= sizeof(T)) if (size >= sizeof(T)) {
*(T *)buf = _value; *(T *)buf = _value;
return sizeof(T); }
} return sizeof(T);
}
// Unserialize from the buffer, but only if it is big enough. // Unserialize from the buffer, but only if it is big enough.
// //
virtual size_t unserialize(void *buf, size_t size) { virtual size_t unserialize(void *buf, size_t size) {
if (size >= sizeof(T)) if (size >= sizeof(T)) {
_value = *(T*)buf; _value = *(T *)buf;
return sizeof(T); }
} return sizeof(T);
}
/// Restore the variable to its default value /// Restore the variable to its default value
virtual void set_default(void) { _value = _defaultValue; } virtual void set_default(void) {
_value = _default_value;
}
/// Value getter /// Value getter
/// ///
T get(void) const { return _value; } T get(void) const {
return _value;
}
/// Value setter /// Value setter
/// ///
void set(T v) { _value = v; } void set(T v) {
_value = v;
}
/// Conversion to T returns a reference to the value. /// Conversion to T returns a reference to the value.
/// ///
/// 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&() { return _value; } operator T &() {
return _value;
}
/// Copy assignment from self does nothing. /// Copy assignment from self does nothing.
/// ///
AP_VarT<T>& operator=(AP_VarT<T>& v) { return v; } AP_VarT<T>& operator=(AP_VarT<T>& v) {
return v;
}
/// Copy assignment from T /// 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; T _default_value;
}; };
/// Convenience macro for defining instances of the AP_Var template /// Convenience macro for defining instances of the AP_Var template
/// ///
#define AP_VARDEF(_t, _n) \ #define AP_VARDEF(_t, _n) typedef AP_VarT<_t> AP_##_n;
typedef AP_VarT<_t> AP_##_n; AP_VARDEF(float, Float); // defines AP_Float
AP_VARDEF(int8_t, Int8); // defines AP_UInt8
AP_VARDEF(float, Float); // defines AP_Float, AP_NamedFloat and AP_SavedFloat AP_VARDEF(int16_t, Int16); // defines AP_UInt16
AP_VARDEF(int8_t, Int8); // defines AP_UInt8, AP_NamedUInt8 and AP_SavedUInt8 AP_VARDEF(int32_t, Int32); // defines AP_UInt32
AP_VARDEF(int16_t, Int16); // defines AP_UInt16, AP_NamedUInt16 and AP_SavedUInt16
AP_VARDEF(int32_t, Int32); // defines AP_UInt32, AP_NamedUInt32 and AP_SavedUInt32
/// Many float values can be saved as 16-bit fixed-point values, reducing EEPROM /// Many float values can be saved as 16-bit fixed-point values, reducing EEPROM
/// consumption. AP_Float16 subclasses AP_Float and overloads serialize/unserialize /// consumption. AP_Float16 subclasses AP_Float and overloads serialize/unserialize
@ -335,40 +334,46 @@ AP_VARDEF(int32_t, Int32); // defines AP_UInt32, AP_NamedUInt32 and AP_SavedUI
class AP_Float16 : public AP_Float 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 default_value = 0,
AP_VarAddress address = AP_VarNoAddress, Address address = k_no_address,
const prog_char *name = NULL, const prog_char *name = NULL,
AP_VarScope *scope = NULL, AP_Var_scope *scope = NULL,
Flags flags = NO_FLAGS) : Flags flags = k_no_flags) :
AP_Float(defaultValue, address, name, scope, flags) AP_Float(default_value, address, name, scope, flags) {
{ }
}
// Serialize _value as Q5.10. // Serialize _value as Q5.10.
// //
virtual size_t serialize(void *buf, size_t size) const { virtual size_t serialize(void *buf, size_t size) const {
uint16_t *sval = (uint16_t *)buf; uint16_t *sval = (uint16_t *)buf;
if (size >= sizeof(*sval)) if (size >= sizeof(*sval)) {
*sval = _value / 1024.0; // scale by power of 2, may be more efficient *sval = _value / 1024.0; // scale by power of 2, may be more efficient
return sizeof(*sval); }
} return sizeof(*sval);
}
// Unserialize _value from Q5.10. // Unserialize _value from Q5.10.
// //
virtual size_t unserialize(void *buf, size_t size) { virtual size_t unserialize(void *buf, size_t size) {
uint16_t *sval = (uint16_t *)buf; uint16_t *sval = (uint16_t *)buf;
if (size >= sizeof(*sval)) if (size >= sizeof(*sval)) {
_value = *sval * 1024.0; // scale by power of 2, may be more efficient _value = *sval * 1024.0; // scale by power of 2, may be more efficient
return sizeof(*sval); }
} return sizeof(*sval);
}
// copy operators must be redefined in subclasses to get correct behaviour // copy operators must be redefined in subclasses to get correct behaviour
AP_Float16& operator=(AP_Float16 &v) { return v; } AP_Float16 &operator=(AP_Float16 &v) {
AP_Float16& operator=(float v) { _value = v; return *this; } return v;
}
AP_Float16 &operator=(float v) {
_value = v;
return *this;
}
}; };
@ -376,8 +381,10 @@ public:
/// ///
/// @todo Work out why these can't be const and fix if possible. /// @todo Work out why these can't be const and fix if possible.
/// ///
extern AP_Float AP_FloatUnity; /// @todo Work out how to get these into a namespace and name them properly.
extern AP_Float AP_FloatNegativeUnity; ///
extern AP_Float AP_FloatZero; extern AP_Float AP_Float_unity;
extern AP_Float AP_Float_negative_unity;
extern AP_Float AP_Float_zero;
#endif // AP_Var_H #endif // AP_VAR_H

View File

@ -1,5 +1,5 @@
// //
// Unit tests for the AP_MetaClass and AP_Var classes. // Unit tests for the AP_Meta_class and AP_Var classes.
// //
#include <FastSerial.h> #include <FastSerial.h>
@ -17,33 +17,33 @@ FastSerialPort(Serial, 0);
class Test class Test
{ {
public: public:
Test(const char *name) : _name(name), _fail(false) {} Test(const char *name) : _name(name), _fail(false) {}
~Test() { ~Test() {
Serial.printf("%s: %s\n", _fail ? "FAILED" : "passed", _name); Serial.printf("%s: %s\n", _fail ? "FAILED" : "passed", _name);
if (_fail) { if (_fail) {
_failed++; _failed++;
} else { } else {
_passed++; _passed++;
} }
} }
void require(bool expr, const char *source) { void require(bool expr, const char *source) {
if (!expr) { if (!expr) {
_fail = true; _fail = true;
Serial.printf("%s: fail: %s\n", _name, source); Serial.printf("%s: fail: %s\n", _name, source);
} }
} }
static void report() { static void report() {
Serial.printf("\n%d passed %d failed\n", _passed, _failed); Serial.printf("\n%d passed %d failed\n", _passed, _failed);
} }
private: private:
const char *_name; const char *_name;
bool _fail; bool _fail;
static int _passed; static int _passed;
static int _failed; static int _failed;
}; };
int Test::_passed = 0; int Test::_passed = 0;
@ -58,247 +58,247 @@ int Test::_failed = 0;
void void
setup(void) setup(void)
{ {
Serial.begin(38400); Serial.begin(38400);
// MetaClass: test type ID // MetaClass: test type ID
{ {
TEST(meta_type_id); TEST(meta_type_id);
AP_Float f1; AP_Float f1;
AP_Float f2; AP_Float f2;
AP_Int8 i1; AP_Int8 i1;
uint16_t m1 = f1.meta_type_id(); uint16_t m1 = f1.meta_type_id();
uint16_t m2 = f2.meta_type_id(); uint16_t m2 = f2.meta_type_id();
uint16_t m3 = i1.meta_type_id(); uint16_t m3 = i1.meta_type_id();
REQUIRE(m1 != 0); REQUIRE(m1 != 0);
REQUIRE(m1 == m2); REQUIRE(m1 == m2);
REQUIRE(m1 != m3); REQUIRE(m1 != m3);
REQUIRE( AP_MetaClass::meta_type_equivalent(&f1, &f2)); REQUIRE(AP_Meta_class::meta_type_equivalent(&f1, &f2));
REQUIRE(!AP_MetaClass::meta_type_equivalent(&f1, &i1)); REQUIRE(!AP_Meta_class::meta_type_equivalent(&f1, &i1));
} }
// MetaClass: test external handles // MetaClass: test external handles
{ {
TEST(meta_handle); TEST(meta_handle);
AP_Float f; AP_Float f;
AP_MetaClass::AP_MetaHandle h = f.meta_get_handle(); AP_Meta_class::Meta_handle h = f.meta_get_handle();
REQUIRE(0 != h); REQUIRE(0 != h);
REQUIRE(NULL != AP_MetaClass::meta_validate_handle(h)); REQUIRE(NULL != AP_Meta_class::meta_validate_handle(h));
REQUIRE(NULL == AP_MetaClass::meta_validate_handle(h + 1)); REQUIRE(NULL == AP_Meta_class::meta_validate_handle(h + 1));
} }
// MetaClass: test meta_cast // MetaClass: test meta_cast
{ {
TEST(meta_cast); TEST(meta_cast);
AP_Float f; AP_Float f;
REQUIRE(NULL != AP_MetaClass::meta_cast<AP_Float>(&f)); REQUIRE(NULL != AP_Meta_class::meta_cast<AP_Float>(&f));
REQUIRE(NULL == AP_MetaClass::meta_cast<AP_Int8>(&f)); REQUIRE(NULL == AP_Meta_class::meta_cast<AP_Int8>(&f));
} }
// MetaClass: ... insert tests here ... // MetaClass: ... insert tests here ...
// AP_Var: constants // AP_Var: constants
{ {
TEST(var_constants); TEST(var_constants);
REQUIRE(AP_FloatZero == 0); REQUIRE(AP_Float_zero == 0);
REQUIRE(AP_FloatUnity == 1.0); REQUIRE(AP_Float_unity == 1.0);
REQUIRE(AP_FloatNegativeUnity = -1.0); REQUIRE(AP_Float_negative_unity = -1.0);
} }
// AP_Var: set, get, assignment // AP_Var: set, get, assignment
{ {
TEST(var_set_get); TEST(var_set_get);
AP_Float f(1.0); AP_Float f(1.0);
REQUIRE(f == 1.0); REQUIRE(f == 1.0);
REQUIRE(f.get() == 1.0); REQUIRE(f.get() == 1.0);
f.set(10.0); f.set(10.0);
REQUIRE(f == 10.0); REQUIRE(f == 10.0);
REQUIRE(f.get() == 10.0); REQUIRE(f.get() == 10.0);
} }
// AP_Var: default value // AP_Var: default value
{ {
TEST(var_default_value); TEST(var_default_value);
AP_Float f(10.0); AP_Float f(10.0);
REQUIRE(f == 10.0); REQUIRE(f == 10.0);
f = 0; f = 0;
REQUIRE(f == 0); REQUIRE(f == 0);
f.set_default(); f.set_default();
REQUIRE(f == 10.0); REQUIRE(f == 10.0);
} }
// AP_Var: cast to type // AP_Var: cast to type
{ {
TEST(var_cast_to_type); TEST(var_cast_to_type);
AP_Float f(1.0); AP_Float f(1.0);
f *= 2.0; f *= 2.0;
REQUIRE(f == 2.0); REQUIRE(f == 2.0);
f /= 4; f /= 4;
REQUIRE(f == 0.5); REQUIRE(f == 0.5);
f += f; f += f;
REQUIRE(f == 1.0); REQUIRE(f == 1.0);
} }
// AP_Var: equality // AP_Var: equality
{ {
TEST(var_equality); TEST(var_equality);
AP_Float f1(1.0); AP_Float f1(1.0);
AP_Float f2(1.0); AP_Float f2(1.0);
AP_Float f3(2.0); AP_Float f3(2.0);
REQUIRE(f1 == f2); REQUIRE(f1 == f2);
REQUIRE(f2 != f3); REQUIRE(f2 != f3);
} }
// AP_Var: naming // AP_Var: naming
{ {
TEST(var_naming); TEST(var_naming);
AP_Float f(0, AP_Var::AP_VarNoAddress, PSTR("test")); AP_Float f(0, AP_Var::k_no_address, PSTR("test"));
char name_buffer[16]; char name_buffer[16];
f.copy_name(name_buffer, sizeof(name_buffer)); f.copy_name(name_buffer, sizeof(name_buffer));
REQUIRE(!strcmp(name_buffer, "test")); REQUIRE(!strcmp(name_buffer, "test"));
} }
// AP_Var: serialize // AP_Var: serialize
{ {
TEST(var_serialize); TEST(var_serialize);
float b = 0; float b = 0;
AP_Float f(10.0); AP_Float f(10.0);
size_t s; size_t s;
s = f.serialize(&b, sizeof(b)); s = f.serialize(&b, sizeof(b));
REQUIRE(s == sizeof(b)); REQUIRE(s == sizeof(b));
REQUIRE(b == 10.0); REQUIRE(b == 10.0);
} }
// AP_Var: unserialize // AP_Var: unserialize
{ {
TEST(var_unserialize); TEST(var_unserialize);
float b = 10; float b = 10;
AP_Float f(0); AP_Float f(0);
size_t s; size_t s;
s = f.unserialize(&b, sizeof(b)); s = f.unserialize(&b, sizeof(b));
REQUIRE(s == sizeof(b)); REQUIRE(s == sizeof(b));
REQUIRE(f == 10); REQUIRE(f == 10);
} }
// AP_Var: load and save // AP_Var: load and save
{ {
TEST(var_load_save); TEST(var_load_save);
AP_Float f1(10, 4); AP_Float f1(10, 4);
AP_Float f2(0, 4); AP_Float f2(0, 4);
f2.save(); f2.save();
f2 = 1.0; f2 = 1.0;
f2.load(); f2.load();
REQUIRE(f2 == 0); REQUIRE(f2 == 0);
f1.save(); f1.save();
f2.load(); f2.load();
REQUIRE(f2 == 10); REQUIRE(f2 == 10);
} }
// AP_Var: enumeration // AP_Var: enumeration
// note that this test presumes the singly-linked list implementation of the list // note that this test presumes the singly-linked list implementation of the list
{ {
TEST(var_enumeration); TEST(var_enumeration);
AP_Var *v = AP_Var::lookup(0); AP_Var *v = AP_Var::lookup(0);
// test basic enumeration // test basic enumeration
AP_Float f1(0, AP_Var::AP_VarNoAddress, PSTR("test1")); AP_Float f1(0, AP_Var::k_no_address, PSTR("test1"));
REQUIRE(AP_Var::lookup(0) == &f1); REQUIRE(AP_Var::lookup(0) == &f1);
REQUIRE(AP_Var::lookup(1) == v); REQUIRE(AP_Var::lookup(1) == v);
// test that new entries arrive in order // test that new entries arrive in order
{ {
AP_Float f2(0, AP_Var::AP_VarNoAddress, PSTR("test2")); AP_Float f2(0, AP_Var::k_no_address, PSTR("test2"));
REQUIRE(AP_Var::lookup(0) == &f2); REQUIRE(AP_Var::lookup(0) == &f2);
REQUIRE(AP_Var::lookup(1) == &f1); REQUIRE(AP_Var::lookup(1) == &f1);
REQUIRE(AP_Var::lookup(2) == v); REQUIRE(AP_Var::lookup(2) == v);
{ {
AP_Float f3(0, AP_Var::AP_VarNoAddress, PSTR("test3")); AP_Float f3(0, AP_Var::k_no_address, PSTR("test3"));
REQUIRE(AP_Var::lookup(0) == &f3); REQUIRE(AP_Var::lookup(0) == &f3);
REQUIRE(AP_Var::lookup(1) == &f2); REQUIRE(AP_Var::lookup(1) == &f2);
REQUIRE(AP_Var::lookup(2) == &f1); REQUIRE(AP_Var::lookup(2) == &f1);
REQUIRE(AP_Var::lookup(3) == v); REQUIRE(AP_Var::lookup(3) == v);
} }
} }
// test that destruction removes from the list // test that destruction removes from the list
REQUIRE(AP_Var::lookup(0) == &f1); REQUIRE(AP_Var::lookup(0) == &f1);
REQUIRE(AP_Var::lookup(1) == v); REQUIRE(AP_Var::lookup(1) == v);
} }
// AP_Var: scope names // AP_Var: scope names
{ {
TEST(var_scope_names); TEST(var_scope_names);
AP_VarScope scope(PSTR("scope_")); AP_Var_scope scope(PSTR("scope_"));
AP_Float f(1.0, AP_Var::AP_VarNoAddress, PSTR("test"), &scope); AP_Float f(1.0, AP_Var::k_no_address, PSTR("test"), &scope);
char name_buffer[16]; char name_buffer[16];
f.copy_name(name_buffer, sizeof(name_buffer)); f.copy_name(name_buffer, sizeof(name_buffer));
REQUIRE(!strcmp(name_buffer, "scope_test")); REQUIRE(!strcmp(name_buffer, "scope_test"));
} }
// AP_Var: scope address offsets // AP_Var: scope address offsets
{ {
TEST(var_scope_addressing); TEST(var_scope_addressing);
AP_VarScope scope(PSTR("scope"), 4); AP_Var_scope scope(PSTR("scope"), 4);
AP_Float f1(10.0, 8); AP_Float f1(10.0, 8);
AP_Float f2(1.0, 4, PSTR("var"), &scope); AP_Float f2(1.0, 4, PSTR("var"), &scope);
f1.save(); f1.save();
f1.load(); f1.load();
REQUIRE(f1 == 10); REQUIRE(f1 == 10);
f2.save(); f2.save();
f2.load(); f2.load();
REQUIRE(f2 == 1); REQUIRE(f2 == 1);
f1.load(); f1.load();
REQUIRE(f1 == 1); REQUIRE(f1 == 1);
} }
// AP_Var: derived types // AP_Var: derived types
{ {
TEST(var_derived); TEST(var_derived);
AP_Float16 f(10.0, 20); AP_Float16 f(10.0, 20);
f.save(); f.save();
f = 0; f = 0;
REQUIRE(f == 0); REQUIRE(f == 0);
f.load(); f.load();
REQUIRE(f = 10.0); REQUIRE(f = 10.0);
} }
Test::report(); Test::report();
} }
void void