diff --git a/libraries/AP_Common/AP_MetaClass.cpp b/libraries/AP_Common/AP_MetaClass.cpp index ea6b028ce8..d47cbd4ce2 100644 --- a/libraries/AP_Common/AP_MetaClass.cpp +++ b/libraries/AP_Common/AP_MetaClass.cpp @@ -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 // the terms of the GNU Lesser General Public License as published by the @@ -14,25 +14,23 @@ #include "AP_MetaClass.h" // 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 // subclasses not overloading the default virtual dtor still have something in their // vtable. -AP_MetaClass::~AP_MetaClass() +AP_Meta_class::~AP_Meta_class() { } -size_t -AP_MetaClass::serialize(void *buf, size_t bufSize) const +size_t AP_Meta_class::serialize(void *buf, size_t bufSize) const { - return 0; + return 0; } -size_t -AP_MetaClass::unserialize(void *buf, size_t bufSize) +size_t AP_Meta_class::unserialize(void *buf, size_t bufSize) { - return 0; + return 0; } diff --git a/libraries/AP_Common/AP_MetaClass.h b/libraries/AP_Common/AP_MetaClass.h index c6915a79e4..f80ef79bf5 100644 --- a/libraries/AP_Common/AP_MetaClass.h +++ b/libraries/AP_Common/AP_MetaClass.h @@ -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 // the terms of the GNU Lesser General Public License as published by the @@ -6,7 +6,7 @@ // 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. /// /// This abstract base class declares and implements functions that are @@ -17,215 +17,217 @@ /// basic functions. /// -#ifndef AP_METACLASS_H -#define AP_METACLASS_H +#ifndef AP_META_CLASS_H +#define AP_META_CLASS_H #include // for size_t #include #include // for RAMEND - /// Basic meta-class from which other AP_* classes can derive. /// /// Functions that form the public API to the metaclass are prefixed meta_. /// -class AP_MetaClass +class AP_Meta_class { public: - /// Default constructor does nothing. - AP_MetaClass(void); + /// Default constructor does nothing. + AP_Meta_class(void); - /// Default destructor is virtual, to ensure that all subclasses' - /// destructors are virtual. This guarantees that all destructors - /// in the inheritance chain are called at destruction time. - /// - virtual ~AP_MetaClass(); + /// Default destructor is virtual, to ensure that all subclasses' + /// destructors are virtual. This guarantees that all destructors + /// in the inheritance chain are called at destruction time. + /// + virtual ~AP_Meta_class(); - /// Typedef for the ID unique to all instances of a class. - /// - /// See ::meta_type_id for a discussion of class type IDs. - /// - typedef uint16_t AP_TypeID; + /// Typedef for the ID unique to all instances of a class. + /// + /// See ::meta_type_id for a discussion of class type IDs. + /// + typedef uint16_t AP_Type_id; - /// Obtain a value unique to all instances of a specific subclass. - /// - /// The value can be used to determine whether two class pointers - /// 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. - /// - /// This is similar to the basic functionality of the C++ typeid - /// keyword, but does not depend on std::type_info or any compiler- - /// generated RTTI. - /// - /// 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 - /// 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 - /// of a class Foo, one would write: - /// - /// AP_MetaClass::AP_TypeID Foo_type_id; - /// - /// { Foo a; Foo_type_id = a.meta_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. - /// @return A type-unique value. - /// - AP_TypeID meta_type_id(void) const { - return *(AP_TypeID *)this; - } + /// Obtain a value unique to all instances of a specific subclass. + /// + /// The value can be used to determine whether two class pointers + /// 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. + /// + /// This is similar to the basic functionality of the C++ typeid + /// keyword, but does not depend on std::type_info or any compiler- + /// generated RTTI. + /// + /// 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 + /// 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 + /// of a class Foo, one would write: + /// + /// AP_Meta_class::AP_Type_id Foo_type_id; + /// + /// { Foo a; Foo_type_id = a.meta_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_Meta_class. + /// @return A type-unique value. + /// + AP_Type_id meta_type_id(void) const { + return *(AP_Type_id *)this; + } - /// External handle for an instance of an AP_MetaClass subclass, contains - /// enough information to construct and validate a pointer to the instance - /// when passed back from an untrusted source. - /// - /// 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 - /// them back. - /// - typedef uint32_t AP_MetaHandle; + /// External handle for an instance of an AP_Meta_class subclass, contains + /// enough information to construct and validate a pointer to the instance + /// when passed back from an untrusted source. + /// + /// 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 + /// them back. + /// + typedef uint32_t Meta_handle; - /// Return a value that can be used as an external pointer to an instance - /// of a subclass. - /// - /// 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 - /// a pointer to the class instance. - /// - /// @return An opaque handle - /// - AP_MetaHandle meta_get_handle(void) const { - return ((AP_MetaHandle)meta_type_id() << 16) | (uint16_t)this; - } + /// Return a value that can be used as an external pointer to an instance + /// of a subclass. + /// + /// 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 + /// a pointer to the class instance. + /// + /// @return An opaque handle + /// + Meta_handle meta_get_handle(void) const { + return ((Meta_handle)meta_type_id() << 16) | (uint16_t)this; + } - /// Validates an AP_MetaClass handle. - /// - /// The value of the handle is not required to be valid; in particular the - /// pointer encoded in the handle is validated before being dereferenced. - /// - /// 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. - /// - /// @param handle A possible AP_MetaClass handle - /// @return The instance pointer if the handle is good, - /// or NULL if it is bad. - /// - static AP_MetaClass *meta_validate_handle(AP_MetaHandle handle) { - AP_MetaClass *candidate = (AP_MetaClass *)(handle & 0xffff); // extract object pointer - uint16_t id = handle >> 16; // and claimed type + /// Validates an AP_Meta_class handle. + /// + /// The value of the handle is not required to be valid; in particular the + /// pointer encoded in the handle is validated before being dereferenced. + /// + /// 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. + /// + /// @param handle A possible AP_Meta_class handle + /// @return The instance pointer if the handle is good, + /// or NULL if it is bad. + /// + static AP_Meta_class *meta_validate_handle(Meta_handle handle) { + AP_Meta_class *candidate = (AP_Meta_class *)(handle & 0xffff); // extract object pointer + uint16_t id = handle >> 16; // and claimed type - // 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. - // 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, - // 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 - return NULL; + // 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. + // 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, + // 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 + return NULL; + } - // 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 - // candidate pointer because meta_type_id is non-virtual (and will in fact be - // inlined here). - // - if (candidate->meta_type_id() == id) - return candidate; + // 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 + // candidate pointer because meta_type_id is non-virtual (and will in fact be + // inlined here). + // + if (candidate->meta_type_id() == id) { + return candidate; + } - return NULL; - } + return NULL; + } - /// 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 - /// 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 - /// that they be passed as pointers to AP_MetaClass in order to make it clear that - /// they should be pointers to classes derived from AP_MetaClass. - /// - /// 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 - /// similar contents, or to non-AP_MetaClass derived classes with no virtual functions - /// this function may return true. - /// - /// @param p1 The first object to be compared. - /// @param p2 The second object to be compared. - /// @return True if the two objects are of the same class, false - /// if they are not. - /// - static bool meta_type_equivalent(AP_MetaClass *p1, AP_MetaClass *p2) { - return p1->meta_type_id() == p2->meta_type_id(); - } + /// 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 + /// 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 + /// 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_Meta_class. + /// + /// No attempt is made to validate whether p1 and p2 are actually derived from + /// AP_Meta_class. If p1 and p2 are equal, or if they point to non-class objects with + /// similar contents, or to non-AP_Meta_class derived classes with no virtual functions + /// this function may return true. + /// + /// @param p1 The first object to be compared. + /// @param p2 The second object to be compared. + /// @return True if the two objects are of the same class, false + /// if they are not. + /// + static bool meta_type_equivalent(AP_Meta_class *p1, AP_Meta_class *p2) { + return p1->meta_type_id() == p2->meta_type_id(); + } - /// Cast a pointer to an expected class type. - /// - /// 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 - /// 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 - /// destructor will be run, possibly introducing undesired side-effects. - /// - /// @todo Consider whether we should make it difficult to have a default constructor - /// with appreciable side-effects. - /// - /// @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 _typename The name of a type with which _p is to be compared. - /// @return True if _p is of type _typename, false otherwise. - /// - template - static T* meta_cast(AP_MetaClass *p) { - T tmp; - if (meta_type_equivalent(p, &tmp)) - return (T *)p; - return NULL; - } + /// Cast a pointer to an expected class type. + /// + /// This function is used when a pointer is expected to be a pointer to a + /// 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. + /// + /// This should be used with caution, as _typename's default constructor and + /// destructor will be run, possibly introducing undesired side-effects. + /// + /// @todo Consider whether we should make it difficult to have a default constructor + /// with appreciable side-effects. + /// + /// @todo Check whether we need to reinterpret_cast to get the right return type. + /// + /// @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. + /// @return True if _p is of type _typename, false otherwise. + /// + template + static T *meta_cast(AP_Meta_class *p) { + T tmp; + if (meta_type_equivalent(p, &tmp)) { + return (T *)p; + } + return NULL; + } - /// Serialize the class. - /// - /// Serialization stores the state of the class in an external buffer in such a - /// fashion that it can later be restored by unserialization. - /// - /// AP_MetaClass subclasses should only implement these functions if saving and - /// restoring their state makes sense. - /// - /// Serialization provides a mechanism for exporting the state of the class to an - /// external consumer, either for external introspection or for subsequent restoration. - /// - /// Classes that wrap variables should define the format of their serialiaed data - /// so that external consumers can reliably interpret it. - /// - /// @param buf Buffer into which serialised data should be placed. - /// @param bufSize The size of the buffer provided. - /// @return The size of the serialised data, even if that data would - /// have overflowed the buffer. If the return value is zero, - /// the class does not support serialization. - /// - virtual size_t serialize(void *buf, size_t bufSize) const; + /// Serialize the class. + /// + /// Serialization stores the state of the class in an external buffer in such a + /// fashion that it can later be restored by unserialization. + /// + /// AP_Meta_class subclasses should only implement these functions if saving and + /// restoring their state makes sense. + /// + /// Serialization provides a mechanism for exporting the state of the class to an + /// external consumer, either for external introspection or for subsequent restoration. + /// + /// Classes that wrap variables should define the format of their serialiaed data + /// so that external consumers can reliably interpret it. + /// + /// @param buf Buffer into which serialised data should be placed. + /// @param bufSize The size of the buffer provided. + /// @return The size of the serialised data, even if that data would + /// have overflowed the buffer. If the return value is zero, + /// the class does not support serialization. + /// + virtual size_t serialize(void *buf, size_t bufSize) const; - /// Unserialize the class. - /// - /// Unserializing a class from a buffer into which the class previously serialized - /// itself restores the instance to an identical state, where "identical" is left - /// up to the class itself to define. - /// - /// Classes that wrap variables should define the format of their serialized data so - /// that external providers can reliably encode it. - /// - /// @param buf Buffer containing serialized data. - /// @param bufSize The size of the buffer. - /// @return The number of bytes from the buffer that would be consumed - /// unserializing the data. If the value is less than or equal - /// to bufSize, unserialization was successful. If the return - /// value is zero the class does not support unserialisation or - /// the data in the buffer is invalid. - /// - virtual size_t unserialize(void *buf, size_t bufSize); + /// Unserialize the class. + /// + /// Unserializing a class from a buffer into which the class previously serialized + /// itself restores the instance to an identical state, where "identical" is left + /// up to the class itself to define. + /// + /// Classes that wrap variables should define the format of their serialized data so + /// that external providers can reliably encode it. + /// + /// @param buf Buffer containing serialized data. + /// @param bufSize The size of the buffer. + /// @return The number of bytes from the buffer that would be consumed + /// unserializing the data. If the value is less than or equal + /// to bufSize, unserialization was successful. If the return + /// value is zero the class does not support unserialisation or + /// the data in the buffer is invalid. + /// + virtual size_t unserialize(void *buf, size_t bufSize); }; -#endif // AP_METACLASS_H +#endif // AP_Meta_class_H diff --git a/libraries/AP_Common/AP_Var.cpp b/libraries/AP_Common/AP_Var.cpp index 72f4dd9a34..a4ea528cd5 100644 --- a/libraries/AP_Common/AP_Var.cpp +++ b/libraries/AP_Common/AP_Var.cpp @@ -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 // the terms of the GNU Lesser General Public License as published by the @@ -13,27 +13,28 @@ // Global constants exported // -AP_Float AP_FloatUnity(1.0); -AP_Float AP_FloatNegativeUnity(-1.0); -AP_Float AP_FloatZero(0); +AP_Float AP_Float_unity(1.0); +AP_Float AP_Float_negative_unity(-1.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 // -AP_Var::AP_Var(AP_VarAddress address, - const prog_char *name, - const AP_VarScope *scope, - Flags flags) : - _address(address), - _name(name), - _scope(scope), - _flags(flags) +AP_Var::AP_Var(Address address, const prog_char *name, const AP_Var_scope *scope, Flags flags) : + _address(address), _name(name), _scope(scope), _flags(flags) { - // link the variable into the list of known variables - _link = _variables; - _variables = this; + // link the variable into the list of known variables + _link = _variables; + _variables = this; - // reset the lookup cache - _lookupHintIndex = 0; + // reset the lookup cache + _lookup_hint_index = 0; } // Destructor @@ -42,183 +43,178 @@ AP_Var::AP_Var(AP_VarAddress address, // AP_Var::~AP_Var(void) { - // if we are at the head of the list - for variables - // recently constructed this is usually the case - if (_variables == this) { - // remove us from the head of the list - _variables = _link; + // if we are at the head of the list - for variables + // recently constructed this is usually the case + if (_variables == this) { + // remove us from the head of the list + _variables = _link; - } else { - // traverse the list looking for the entry that points to us - AP_Var *p = _variables; + } else { + // traverse the list looking for the entry that points to us + AP_Var *p = _variables; - while (p) { - // is it pointing at us? - if (p->_link == this) { - // make it point at what we point at, and done - p->_link = _link; - break; - } - // try the next one - p = p->_link; - } - } + while (p) { + // is it pointing at us? + if (p->_link == this) { + // make it point at what we point at, and done + p->_link = _link; + break; + } + // try the next one + p = p->_link; + } + } - // reset the lookup cache - _lookupHintIndex = 0; + // reset the lookup cache + _lookup_hint_index = 0; } -void -AP_Var::set_default(void) +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. // -void -AP_Var::copy_name(char *buffer, size_t bufferSize) const +void AP_Var::copy_name(char *buffer, size_t buffer_size) const { - buffer[0] = '\0'; - if (_scope) - _scope->copy_name(buffer, bufferSize); - strlcat_P(buffer, _name, bufferSize); + buffer[0] = '\0'; + if (_scope) { + _scope->copy_name(buffer, buffer_size); + } + strlcat_P(buffer, _name, buffer_size); } // 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. // -AP_Var::AP_VarAddress -AP_VarScope::get_address(void) const +AP_Var::Address AP_Var_scope::get_address(void) const { - AP_Var::AP_VarAddress addr = _address; + AP_Var::Address addr = _address; - if (_parent) - addr += _parent->get_address(); + if (_parent) { + addr += _parent->get_address(); + } - return addr; + return addr; } // Compute the address in EEPROM where the variable is stored // -AP_Var::AP_VarAddress -AP_Var::_get_address(void) const +AP_Var::Address AP_Var::_get_address(void) const { - AP_VarAddress addr = _address; + Address addr = _address; - // if we have an address at all - if ((addr != AP_VarNoAddress) && _scope) - addr += _scope->get_address(); + // if we have an address at all + if ((addr != k_no_address) && _scope) { + addr += _scope->get_address(); + } - return addr; + return addr; } // Save the variable to EEPROM, if supported // -void -AP_Var::save(void) const +void AP_Var::save(void) const { - AP_VarAddress addr = _get_address(); + Address addr = _get_address(); - if (addr != AP_VarNoAddress) { - uint8_t vbuf[AP_VarMaxSize]; - size_t size; + if (addr != k_no_address) { + uint8_t vbuf[k_max_size]; + size_t size; - // serialize the variable into the buffer and work out how big it is - size = serialize(vbuf, sizeof(vbuf)); + // serialize the variable into the buffer and work out how big it is + size = serialize(vbuf, sizeof(vbuf)); - // if it fit in the buffer, save it to EEPROM - if (size <= sizeof(vbuf)) - eeprom_write_block(vbuf, (void *)addr, size); - } + // if it fit in the buffer, save it to EEPROM + if (size <= sizeof(vbuf)) { + eeprom_write_block(vbuf, (void *)addr, size); + } + } } // Load the variable from EEPROM, if supported // -void -AP_Var::load(void) +void AP_Var::load(void) { - AP_VarAddress addr = _get_address(); + Address addr = _get_address(); - if (addr != AP_VarNoAddress) { - uint8_t vbuf[AP_VarMaxSize]; - size_t size; + if (addr != k_no_address) { + uint8_t vbuf[k_max_size]; + size_t size; - // ask the unserializer how big the variable is - size = unserialize(NULL, 0); + // ask the unserializer how big the variable is + size = unserialize(NULL, 0); - // read the buffer from EEPROM - if (size <= sizeof(vbuf)) { - eeprom_read_block(vbuf, (void *)addr, size); - unserialize(vbuf, size); - } - } + // read the buffer from EEPROM + if (size <= sizeof(vbuf)) { + eeprom_read_block(vbuf, (void *)addr, size); + unserialize(vbuf, size); + } + } } - // // 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::lookup(int index) { - AP_Var *p; - int i; + AP_Var *p; + int i; - // establish initial search state - if (_lookupHintIndex && // we have a cached hint - (index >= _lookupHintIndex)) { // the desired index is at or after the hint + // establish initial search state + if (_lookup_hint_index && // we have a cached hint + (index >= _lookup_hint_index)) { // the desired index is at or after the hint - p = _lookupHint; // start at the hint point - i = index - _lookupHintIndex; // count only the distance from the hint to the index - } else { + 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 - } + p = _variables; // start at the beginning of the list + i = index; // count to the index + } - // search - while (i-- && p) // count until we hit the index or the end of the list - p = p->_link; + // search + while (i-- && p) { // count until we hit the index or the end of the list + p = p->_link; + } - // update the cache on hit - if (p) { - _lookupHintIndex = index; - _lookupHint = p; - } + // update the cache on hit + if (p) { + _lookup_hint_index = index; + _lookup_hint = p; + } - return(p); + return (p); } // Save all variables that have an identity. // -void -AP_Var::save_all(void) +void AP_Var::save_all(void) { - AP_Var *p = _variables; + AP_Var *p = _variables; - while (p) { - if (!p->has_flags(NO_AUTO_LOAD)) - p->save(); - p = p->_link; - } + while (p) { + if (!p->has_flags(k_no_auto_load)) { + p->save(); + } + p = p->_link; + } } // Load all variables that have an identity. // -void -AP_Var::load_all(void) +void AP_Var::load_all(void) { - AP_Var *p = _variables; + AP_Var *p = _variables; - while (p) { - if (!p->has_flags(NO_AUTO_LOAD)) - p->load(); - p = p->_link; - } + while (p) { + if (!p->has_flags(k_no_auto_load)) { + p->load(); + } + p = p->_link; + } } diff --git a/libraries/AP_Common/AP_Var.h b/libraries/AP_Common/AP_Var.h index 319a3cb1d7..864918835a 100644 --- a/libraries/AP_Common/AP_Var.h +++ b/libraries/AP_Common/AP_Var.h @@ -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 // 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 /// math, memory management, etc. -#ifndef AP_Var_H -#define AP_Var_H +#ifndef AP_VAR_H +#define AP_VAR_H #include #include #include @@ -27,147 +27,147 @@ #include "AP_MetaClass.h" -class AP_VarScope; +class AP_Var_scope; /// Base class for variables. /// /// Provides naming and lookup services for variables. /// -class AP_Var : public AP_MetaClass +class AP_Var : public AP_Meta_class { public: - /// Storage address for variables that can be saved to EEPROM - /// - /// If the variable is contained within a scope, then the address - /// is relative to the scope. - /// - /// @todo This might be used as a token for mass serialisation, - /// but for now it's just the address of the variable's backing - /// store in EEPROM. - /// - typedef uint16_t AP_VarAddress; + /// Storage address for variables that can be saved to EEPROM + /// + /// If the variable is contained within a scope, then the address + /// is relative to the scope. + /// + /// @todo This might be used as a token for mass serialisation, + /// but for now it's just the address of the variable's backing + /// store in EEPROM. + /// + typedef uint16_t Address; - /// 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 - /// EEPROM smaller than 64K. - /// - /// This value is normally the default. - /// - static const AP_VarAddress AP_VarNoAddress = ~(AP_VarAddress)0; + /// 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 + /// EEPROM smaller than 64K. + /// + /// This value is normally the default. + /// + static const Address k_no_address = ~(Address)0; - /// 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. - /// - static const size_t AP_VarMaxSize = 16; + /// 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. + /// + static const size_t k_max_size = 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 - }; + /// Optional flags affecting the behavior and usage of the variable. + /// + enum Flags { + k_no_flags = 0, + k_no_auto_load = (1 << 0), ///< will not be loaded by ::load_all or saved by ::save_all + k_no_import = (1 << 1) ///< new values must not be imported from e.g. a GCS + }; - /// Constructor - /// - /// @param name An optional name by which the variable may be known. - /// This name may be looked up via the ::lookup function. - /// @param scope An optional scope that the variable may be a contained within. - /// The scope's name will be prepended to the variable name - /// by ::copy_name. - /// - AP_Var(AP_VarAddress address = AP_VarNoAddress, - const prog_char *name = NULL, - const AP_VarScope *scope = NULL, - Flags flags = NO_FLAGS); + /// Constructor + /// + /// @param name An optional name by which the variable may be known. + /// This name may be looked up via the ::lookup function. + /// @param scope An optional scope that the variable may be a contained within. + /// The scope's name will be prepended to the variable name + /// by ::copy_name. + /// + AP_Var(Address address = k_no_address, const prog_char *name = NULL, const AP_Var_scope *scope = NULL, + Flags flags = k_no_flags); - /// 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. - /// - ~AP_Var(void); + /// 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. + /// + ~AP_Var(void); - /// Set the variable to its default value - /// - virtual void set_default(void); + /// Set the variable to its default value + /// + virtual void set_default(void); - /// Copy the variable's name, prefixed by any parent class names, to a buffer. - /// - /// 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 - /// result in the buffer will be truncated. - /// - /// @param buffer The destination buffer - /// @param bufferSize Total size of the destination buffer. - /// - void copy_name(char *buffer, size_t bufferSize) const; + /// 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. + /// + /// Note that if the combination of names is larger than the buffer, the + /// result in the buffer will be truncated. + /// + /// @param buffer The destination buffer + /// @param bufferSize Total size of the destination buffer. + /// + 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 that are considered - /// 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 - /// the static construction order. - /// - /// @param index enumerator for the variable to be returned - /// - static AP_Var *lookup(int index); + /// Return a pointer to the n'th known variable. + /// + /// 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. + /// + /// Note that variable index numbers are not constant, they depend on the + /// the static construction order. + /// + /// @param index enumerator for the variable to be returned + /// + static AP_Var *lookup(int index); - /// Save the current value of the variable to EEPROM. - /// - /// This interface works for any subclass that implements - /// serialize. - /// - void save(void) const; + /// Save the current value of the variable to EEPROM. + /// + /// This interface works for any subclass that implements + /// serialize. + /// + void save(void) const; - /// Load the variable from EEPROM. - /// - /// This interface works for any subclass that implements - /// unserialize. - /// - void load(void); + /// Load the variable from EEPROM. + /// + /// This interface works for any subclass that implements + /// unserialize. + /// + void load(void); - /// Save all variables to EEPROM - /// - static void save_all(void); + /// Save all variables to EEPROM + /// + static void save_all(void); - /// Load all variables from EEPROM - /// - static void load_all(void); + /// Load all variables from EEPROM + /// + 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; } + /// 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: - const AP_VarAddress _address; - const prog_char *_name; - const AP_VarScope * const _scope; - AP_Var *_link; - uint8_t _flags; + const Address _address; + const prog_char *_name; + const AP_Var_scope *const _scope; + AP_Var *_link; + uint8_t _flags; - /// Do the arithmetic required to compute the variable's address in EEPROM - /// - /// @returns The address at which the variable is stored in EEPROM, - /// or AP_VarNoAddress if it is not saved. - /// - AP_VarAddress _get_address(void) const; + /// Do the arithmetic required to compute the variable's address in EEPROM + /// + /// @returns The address at which the variable is stored in EEPROM, + /// or k_no_address if it is not saved. + /// + Address _get_address(void) const; - // static state used by ::lookup - static AP_Var *_variables; - static AP_Var *_lookupHint; /// 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 state used by ::lookup + static AP_Var *_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 }; /// Nestable scopes for variable names. @@ -184,55 +184,49 @@ private: /// into account the address offsets of each of the variable's /// enclosing scopes. /// -class AP_VarScope +class AP_Var_scope { public: - /// Constructor - /// - /// @param name The name of the scope. - /// @param address An EEPROM address offset to be added to the address assigned to - /// any variables within the scope. - /// @param parent Optional parent scope to nest within. - /// - AP_VarScope(const prog_char *name, - AP_Var::AP_VarAddress address = 0, - AP_VarScope *parent = NULL) : - _name(name), - _parent(parent), - _address(address) - { - } + /// Constructor + /// + /// @param name The name of the scope. + /// @param address An EEPROM address offset to be added to the address assigned to + /// any variables within the scope. + /// @param parent Optional parent scope to nest within. + /// + AP_Var_scope(const prog_char *name, AP_Var::Address address = 0, AP_Var_scope *parent = NULL) : + _name(name), _parent(parent), _address(address) { + } - /// 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 - /// result in the buffer will be truncated. - /// - /// @param buffer The destination buffer - /// @param bufferSize Total size of the destination buffer. - /// - void copy_name(char *buffer, size_t bufferSize) const - { - if (_parent) - _parent->copy_name(buffer, bufferSize); - strlcat_P(buffer, _name, bufferSize); - } + /// 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 + /// result in the buffer will be truncated. + /// + /// @param buffer The destination buffer + /// @param bufferSize Total size of the destination buffer. + /// + void copy_name(char *buffer, size_t bufferSize) const { + if (_parent) { + _parent->copy_name(buffer, bufferSize); + } + strlcat_P(buffer, _name, bufferSize); + } - /// Compute the address offset that this and any parent scope might apply - /// to variables inside the scope. - /// - /// This provides a way for variables to be grouped into collections whose - /// EEPROM addresses can be more easily managed. - /// - AP_Var::AP_VarAddress get_address(void) const; + /// Compute the address offset that this and any parent scope might apply + /// to variables inside the scope. + /// + /// This provides a way for variables to be grouped into collections whose + /// EEPROM addresses can be more easily managed. + /// + AP_Var::Address get_address(void) const; private: - 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::AP_VarAddress _address; /// container base address, offsets contents + const prog_char *_name; /// pointer to the scope name in program memory + AP_Var_scope *_parent; /// pointer to a parent scope, if one exists + AP_Var::Address _address; /// container base address, offsets contents }; - /// Template class for scalar variables. /// /// Objects of this type have a value, and can be treated in many ways as though they @@ -244,86 +238,91 @@ template class AP_VarT : public AP_Var { public: - /// Constructor - /// - /// @note Constructors for AP_Var are specialised so that they can - /// pass the correct typeCode argument to the AP_Var ctor. - /// - /// @param initialValue Value the variable should have at startup. - /// @param identity A unique token used when saving the variable to EEPROM. - /// Note that this token must be unique, and should only be - /// changed for a variable if the EEPROM version is updated - /// to prevent the accidental unserialisation of old data - /// into the wrong variable. - /// @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. - /// - AP_VarT(T defaultValue = 0, - AP_VarAddress address = AP_VarNoAddress, - const prog_char *name = NULL, - AP_VarScope *scope = NULL, - Flags flags = NO_FLAGS) : - AP_Var(address, name, scope, flags), - _value(defaultValue), - _defaultValue(defaultValue) - { - } + /// Constructor + /// + /// @note Constructors for AP_Var are specialised so that they can + /// pass the correct typeCode argument to the AP_Var ctor. + /// + /// @param initialValue Value the variable should have at startup. + /// @param identity A unique token used when saving the variable to EEPROM. + /// Note that this token must be unique, and should only be + /// changed for a variable if the EEPROM version is updated + /// to prevent the accidental unserialisation of old data + /// into the wrong variable. + /// @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. + /// + AP_VarT (T default_value = 0, Address address = k_no_address, const prog_char *name = NULL, + AP_Var_scope *scope = NULL, Flags flags = k_no_flags) : + AP_Var(address, name, scope, flags), _value(default_value), _default_value(default_value) { + } - // serialize _value into the buffer, but only if it is big enough. - // - virtual size_t serialize(void *buf, size_t size) const { - if (size >= sizeof(T)) - *(T *)buf = _value; - return sizeof(T); - } + // serialize _value into the buffer, but only if it is big enough. + // + virtual size_t serialize(void *buf, size_t size) const { + if (size >= sizeof(T)) { + *(T *)buf = _value; + } + return sizeof(T); + } - // Unserialize from the buffer, but only if it is big enough. - // - virtual size_t unserialize(void *buf, size_t size) { - if (size >= sizeof(T)) - _value = *(T*)buf; - return sizeof(T); - } + // Unserialize from the buffer, but only if it is big enough. + // + virtual size_t unserialize(void *buf, size_t size) { + if (size >= sizeof(T)) { + _value = *(T *)buf; + } + return sizeof(T); + } - /// Restore the variable to its default value - virtual void set_default(void) { _value = _defaultValue; } + /// Restore the variable to its default value + virtual void set_default(void) { + _value = _default_value; + } - /// Value getter - /// - T get(void) const { return _value; } + /// Value getter + /// + T get(void) const { + return _value; + } - /// Value setter - /// - void set(T v) { _value = v; } + /// Value setter + /// + void set(T v) { + _value = v; + } - /// 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. - /// - operator T&() { return _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. + /// + operator T &() { + return _value; + } - /// Copy assignment from self does nothing. - /// - AP_VarT& operator=(AP_VarT& v) { return v; } + /// Copy assignment from self does nothing. + /// + AP_VarT& operator=(AP_VarT& v) { + return v; + } - /// Copy assignment from T - AP_VarT& operator=(T v) { _value = v; return *this; } + /// Copy assignment from T + AP_VarT& operator=(T v) { + _value = v; + return *this; + } protected: - T _value; - T _defaultValue; + T _value; + T _default_value; }; - - /// Convenience macro for defining instances of the AP_Var template /// -#define AP_VARDEF(_t, _n) \ - typedef AP_VarT<_t> AP_##_n; - -AP_VARDEF(float, Float); // defines AP_Float, AP_NamedFloat and AP_SavedFloat -AP_VARDEF(int8_t, Int8); // defines AP_UInt8, AP_NamedUInt8 and AP_SavedUInt8 -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 +#define AP_VARDEF(_t, _n) typedef AP_VarT<_t> AP_##_n; +AP_VARDEF(float, Float); // defines AP_Float +AP_VARDEF(int8_t, Int8); // defines AP_UInt8 +AP_VARDEF(int16_t, Int16); // defines AP_UInt16 +AP_VARDEF(int32_t, Int32); // defines AP_UInt32 /// Many float values can be saved as 16-bit fixed-point values, reducing EEPROM /// 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 { public: - /// Constructor mimics AP_Float::AP_Float() - /// - AP_Float16(float defaultValue = 0, - AP_VarAddress address = AP_VarNoAddress, - const prog_char *name = NULL, - AP_VarScope *scope = NULL, - Flags flags = NO_FLAGS) : - AP_Float(defaultValue, address, name, scope, flags) - { - } + /// Constructor mimics AP_Float::AP_Float() + /// + AP_Float16(float default_value = 0, + Address address = k_no_address, + const prog_char *name = NULL, + AP_Var_scope *scope = NULL, + Flags flags = k_no_flags) : + AP_Float(default_value, address, name, scope, flags) { + } - // Serialize _value as Q5.10. - // - virtual size_t serialize(void *buf, size_t size) const { - uint16_t *sval = (uint16_t *)buf; + // Serialize _value as Q5.10. + // + virtual size_t serialize(void *buf, size_t size) const { + uint16_t *sval = (uint16_t *)buf; - if (size >= sizeof(*sval)) - *sval = _value / 1024.0; // scale by power of 2, may be more efficient - return sizeof(*sval); - } + if (size >= sizeof(*sval)) { + *sval = _value / 1024.0; // scale by power of 2, may be more efficient + } + return sizeof(*sval); + } - // Unserialize _value from Q5.10. - // - virtual size_t unserialize(void *buf, size_t size) { - uint16_t *sval = (uint16_t *)buf; + // Unserialize _value from Q5.10. + // + virtual size_t unserialize(void *buf, size_t size) { + uint16_t *sval = (uint16_t *)buf; - if (size >= sizeof(*sval)) - _value = *sval * 1024.0; // scale by power of 2, may be more efficient - return sizeof(*sval); - } + if (size >= sizeof(*sval)) { + _value = *sval * 1024.0; // scale by power of 2, may be more efficient + } + return sizeof(*sval); + } - // copy operators must be redefined in subclasses to get correct behaviour - AP_Float16& operator=(AP_Float16 &v) { return v; } - AP_Float16& operator=(float v) { _value = v; return *this; } + // copy operators must be redefined in subclasses to get correct behaviour + AP_Float16 &operator=(AP_Float16 &v) { + 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. /// -extern AP_Float AP_FloatUnity; -extern AP_Float AP_FloatNegativeUnity; -extern AP_Float AP_FloatZero; +/// @todo Work out how to get these into a namespace and name them properly. +/// +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 diff --git a/libraries/AP_Common/examples/AP_Var/AP_Var.pde b/libraries/AP_Common/examples/AP_Var/AP_Var.pde index 1d87d2aa75..78008386d6 100644 --- a/libraries/AP_Common/examples/AP_Var/AP_Var.pde +++ b/libraries/AP_Common/examples/AP_Var/AP_Var.pde @@ -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 @@ -17,33 +17,33 @@ FastSerialPort(Serial, 0); class Test { public: - Test(const char *name) : _name(name), _fail(false) {} + Test(const char *name) : _name(name), _fail(false) {} - ~Test() { - Serial.printf("%s: %s\n", _fail ? "FAILED" : "passed", _name); - if (_fail) { - _failed++; - } else { - _passed++; - } - } + ~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); - } - } + 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); - } + static void report() { + Serial.printf("\n%d passed %d failed\n", _passed, _failed); + } private: - const char *_name; - bool _fail; - static int _passed; - static int _failed; + const char *_name; + bool _fail; + static int _passed; + static int _failed; }; int Test::_passed = 0; @@ -58,247 +58,247 @@ int Test::_failed = 0; void setup(void) { - Serial.begin(38400); + Serial.begin(38400); - // MetaClass: test type ID - { - TEST(meta_type_id); + // MetaClass: test type ID + { + TEST(meta_type_id); - AP_Float f1; - AP_Float f2; - AP_Int8 i1; + AP_Float f1; + AP_Float f2; + AP_Int8 i1; - uint16_t m1 = f1.meta_type_id(); - uint16_t m2 = f2.meta_type_id(); - uint16_t m3 = i1.meta_type_id(); + uint16_t m1 = f1.meta_type_id(); + uint16_t m2 = f2.meta_type_id(); + uint16_t m3 = i1.meta_type_id(); - REQUIRE(m1 != 0); - REQUIRE(m1 == m2); - REQUIRE(m1 != m3); - REQUIRE( AP_MetaClass::meta_type_equivalent(&f1, &f2)); - REQUIRE(!AP_MetaClass::meta_type_equivalent(&f1, &i1)); - } + 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)); + } - // MetaClass: test external handles - { - TEST(meta_handle); + // MetaClass: test external handles + { + TEST(meta_handle); - AP_Float f; - AP_MetaClass::AP_MetaHandle h = f.meta_get_handle(); + AP_Float f; + AP_Meta_class::Meta_handle h = f.meta_get_handle(); - REQUIRE(0 != h); - REQUIRE(NULL != AP_MetaClass::meta_validate_handle(h)); - REQUIRE(NULL == AP_MetaClass::meta_validate_handle(h + 1)); - } + REQUIRE(0 != h); + REQUIRE(NULL != AP_Meta_class::meta_validate_handle(h)); + REQUIRE(NULL == AP_Meta_class::meta_validate_handle(h + 1)); + } - // MetaClass: test meta_cast - { - TEST(meta_cast); + // MetaClass: test meta_cast + { + TEST(meta_cast); - AP_Float f; + AP_Float f; - REQUIRE(NULL != AP_MetaClass::meta_cast(&f)); - REQUIRE(NULL == AP_MetaClass::meta_cast(&f)); - } + REQUIRE(NULL != AP_Meta_class::meta_cast(&f)); + REQUIRE(NULL == AP_Meta_class::meta_cast(&f)); + } - // MetaClass: ... insert tests here ... + // MetaClass: ... insert tests here ... - // AP_Var: constants - { - TEST(var_constants); + // AP_Var: constants + { + TEST(var_constants); - REQUIRE(AP_FloatZero == 0); - REQUIRE(AP_FloatUnity == 1.0); - REQUIRE(AP_FloatNegativeUnity = -1.0); - } + REQUIRE(AP_Float_zero == 0); + REQUIRE(AP_Float_unity == 1.0); + REQUIRE(AP_Float_negative_unity = -1.0); + } - // AP_Var: set, get, assignment - { - TEST(var_set_get); + // AP_Var: set, get, assignment + { + TEST(var_set_get); - AP_Float f(1.0); + AP_Float f(1.0); - REQUIRE(f == 1.0); - REQUIRE(f.get() == 1.0); + REQUIRE(f == 1.0); + REQUIRE(f.get() == 1.0); - f.set(10.0); - REQUIRE(f == 10.0); - REQUIRE(f.get() == 10.0); - } + f.set(10.0); + REQUIRE(f == 10.0); + REQUIRE(f.get() == 10.0); + } - // AP_Var: default value - { - TEST(var_default_value); + // AP_Var: default value + { + TEST(var_default_value); - AP_Float f(10.0); + AP_Float f(10.0); - REQUIRE(f == 10.0); - f = 0; - REQUIRE(f == 0); - f.set_default(); - REQUIRE(f == 10.0); - } + REQUIRE(f == 10.0); + f = 0; + REQUIRE(f == 0); + f.set_default(); + REQUIRE(f == 10.0); + } - // AP_Var: cast to type - { - TEST(var_cast_to_type); + // AP_Var: cast to type + { + TEST(var_cast_to_type); - AP_Float f(1.0); + AP_Float f(1.0); - f *= 2.0; - REQUIRE(f == 2.0); - f /= 4; - REQUIRE(f == 0.5); - f += f; - REQUIRE(f == 1.0); - } + f *= 2.0; + REQUIRE(f == 2.0); + f /= 4; + REQUIRE(f == 0.5); + f += f; + REQUIRE(f == 1.0); + } - // AP_Var: equality - { - TEST(var_equality); + // AP_Var: equality + { + TEST(var_equality); - AP_Float f1(1.0); - AP_Float f2(1.0); - AP_Float f3(2.0); + AP_Float f1(1.0); + AP_Float f2(1.0); + AP_Float f3(2.0); - REQUIRE(f1 == f2); - REQUIRE(f2 != f3); - } + REQUIRE(f1 == f2); + REQUIRE(f2 != f3); + } - // AP_Var: naming - { - TEST(var_naming); + // AP_Var: naming + { + TEST(var_naming); - AP_Float f(0, AP_Var::AP_VarNoAddress, PSTR("test")); - char name_buffer[16]; + AP_Float f(0, AP_Var::k_no_address, PSTR("test")); + char name_buffer[16]; - f.copy_name(name_buffer, sizeof(name_buffer)); - REQUIRE(!strcmp(name_buffer, "test")); - } + f.copy_name(name_buffer, sizeof(name_buffer)); + REQUIRE(!strcmp(name_buffer, "test")); + } - // AP_Var: serialize - { - TEST(var_serialize); + // AP_Var: serialize + { + TEST(var_serialize); - float b = 0; - AP_Float f(10.0); - size_t s; + float b = 0; + AP_Float f(10.0); + size_t s; - s = f.serialize(&b, sizeof(b)); - REQUIRE(s == sizeof(b)); - REQUIRE(b == 10.0); - } + s = f.serialize(&b, sizeof(b)); + REQUIRE(s == sizeof(b)); + REQUIRE(b == 10.0); + } - // AP_Var: unserialize - { - TEST(var_unserialize); + // AP_Var: unserialize + { + TEST(var_unserialize); - float b = 10; - AP_Float f(0); - size_t s; + float b = 10; + AP_Float f(0); + size_t s; - s = f.unserialize(&b, sizeof(b)); - REQUIRE(s == sizeof(b)); - REQUIRE(f == 10); - } + s = f.unserialize(&b, sizeof(b)); + REQUIRE(s == sizeof(b)); + REQUIRE(f == 10); + } - // AP_Var: load and save - { - TEST(var_load_save); + // AP_Var: load and save + { + TEST(var_load_save); - AP_Float f1(10, 4); - AP_Float f2(0, 4); + AP_Float f1(10, 4); + AP_Float f2(0, 4); - f2.save(); - f2 = 1.0; - f2.load(); - REQUIRE(f2 == 0); + f2.save(); + f2 = 1.0; + f2.load(); + REQUIRE(f2 == 0); - f1.save(); - f2.load(); - REQUIRE(f2 == 10); - } + f1.save(); + f2.load(); + REQUIRE(f2 == 10); + } - // AP_Var: enumeration - // note that this test presumes the singly-linked list implementation of the list - { - TEST(var_enumeration); + // AP_Var: enumeration + // note that this test presumes the singly-linked list implementation of the list + { + TEST(var_enumeration); - AP_Var *v = AP_Var::lookup(0); + AP_Var *v = AP_Var::lookup(0); - // test basic enumeration - AP_Float f1(0, AP_Var::AP_VarNoAddress, PSTR("test1")); - REQUIRE(AP_Var::lookup(0) == &f1); - REQUIRE(AP_Var::lookup(1) == v); + // test basic enumeration + AP_Float f1(0, AP_Var::k_no_address, PSTR("test1")); + REQUIRE(AP_Var::lookup(0) == &f1); + REQUIRE(AP_Var::lookup(1) == v); - // test that new entries arrive in order - { - AP_Float f2(0, AP_Var::AP_VarNoAddress, PSTR("test2")); - REQUIRE(AP_Var::lookup(0) == &f2); - REQUIRE(AP_Var::lookup(1) == &f1); - REQUIRE(AP_Var::lookup(2) == v); + // test that new entries arrive in order + { + AP_Float f2(0, AP_Var::k_no_address, PSTR("test2")); + REQUIRE(AP_Var::lookup(0) == &f2); + REQUIRE(AP_Var::lookup(1) == &f1); + REQUIRE(AP_Var::lookup(2) == v); - { - AP_Float f3(0, AP_Var::AP_VarNoAddress, PSTR("test3")); - REQUIRE(AP_Var::lookup(0) == &f3); - REQUIRE(AP_Var::lookup(1) == &f2); - REQUIRE(AP_Var::lookup(2) == &f1); - REQUIRE(AP_Var::lookup(3) == v); - } - } + { + AP_Float f3(0, AP_Var::k_no_address, PSTR("test3")); + REQUIRE(AP_Var::lookup(0) == &f3); + REQUIRE(AP_Var::lookup(1) == &f2); + REQUIRE(AP_Var::lookup(2) == &f1); + REQUIRE(AP_Var::lookup(3) == v); + } + } - // test that destruction removes from the list - REQUIRE(AP_Var::lookup(0) == &f1); - REQUIRE(AP_Var::lookup(1) == v); - } + // test that destruction removes from the list + REQUIRE(AP_Var::lookup(0) == &f1); + REQUIRE(AP_Var::lookup(1) == v); + } - // AP_Var: scope names - { - TEST(var_scope_names); + // AP_Var: scope names + { + TEST(var_scope_names); - AP_VarScope scope(PSTR("scope_")); - AP_Float f(1.0, AP_Var::AP_VarNoAddress, PSTR("test"), &scope); - char name_buffer[16]; + AP_Var_scope scope(PSTR("scope_")); + AP_Float f(1.0, AP_Var::k_no_address, PSTR("test"), &scope); + char name_buffer[16]; - f.copy_name(name_buffer, sizeof(name_buffer)); - REQUIRE(!strcmp(name_buffer, "scope_test")); - } + f.copy_name(name_buffer, sizeof(name_buffer)); + REQUIRE(!strcmp(name_buffer, "scope_test")); + } - // AP_Var: scope address offsets - { - TEST(var_scope_addressing); + // AP_Var: scope address offsets + { + TEST(var_scope_addressing); - AP_VarScope scope(PSTR("scope"), 4); - AP_Float f1(10.0, 8); - AP_Float f2(1.0, 4, PSTR("var"), &scope); + AP_Var_scope scope(PSTR("scope"), 4); + AP_Float f1(10.0, 8); + AP_Float f2(1.0, 4, PSTR("var"), &scope); - f1.save(); - f1.load(); - REQUIRE(f1 == 10); + f1.save(); + f1.load(); + REQUIRE(f1 == 10); - f2.save(); - f2.load(); - REQUIRE(f2 == 1); + f2.save(); + f2.load(); + REQUIRE(f2 == 1); - f1.load(); - REQUIRE(f1 == 1); - } + f1.load(); + REQUIRE(f1 == 1); + } - // AP_Var: derived types - { - TEST(var_derived); + // AP_Var: derived types + { + TEST(var_derived); - AP_Float16 f(10.0, 20); + AP_Float16 f(10.0, 20); - f.save(); - f = 0; - REQUIRE(f == 0); - f.load(); - REQUIRE(f = 10.0); - } + f.save(); + f = 0; + REQUIRE(f == 0); + f.load(); + REQUIRE(f = 10.0); + } - Test::report(); + Test::report(); } void