63643f73fc
AP_Vars with either a name or an address are 'interesting' (the latter so we can save_all). Add the concept of address offsets to scopes. Now we have a container that we can put AP_Vars into that can be moved around in the EEPROM. This will make it easier for things like the PID library which need to support multiple instances getting their parameters from different parts of the ROM. Improve documentation. Suck it up and admit that we aren't going to do "identity"-based addressing for the EEPROM and just call the property "address". git-svn-id: https://arducopter.googlecode.com/svn/trunk@1417 f9c3cf11-9bcb-44bc-f272-b75c42450872
287 lines
8.7 KiB
C++
287 lines
8.7 KiB
C++
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
|
//
|
|
// 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
|
|
// Free Software Foundation; either version 2.1 of the License, or (at
|
|
// your option) any later version.
|
|
//
|
|
/// The AP variable interface. This allows different types
|
|
/// of variables to be passed to blocks for floating point
|
|
/// math, memory management, etc.
|
|
|
|
#ifndef AP_Var_H
|
|
#define AP_Var_H
|
|
#include <stddef.h>
|
|
#include <string.h>
|
|
#include <stdint.h>
|
|
|
|
#include <avr/pgmspace.h>
|
|
#include <avr/eeprom.h>
|
|
|
|
#include "AP_MetaClass.h"
|
|
|
|
class AP_VarScope;
|
|
|
|
/// Base class for variables.
|
|
///
|
|
/// Provides naming and lookup services for variables.
|
|
///
|
|
class AP_Var : public AP_MetaClass
|
|
{
|
|
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;
|
|
|
|
/// An address value that indicates that a variable is not to be saved to EEPROM.
|
|
/// This value is normally the default.
|
|
///
|
|
static const AP_VarAddress AP_VarNoAddress = !(AP_VarAddress)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;
|
|
|
|
/// 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);
|
|
|
|
/// Destructor
|
|
///
|
|
/// Note that the linked-list removal can be inefficient when named variables
|
|
/// are destroyed in an order other than the reverse of the order in which
|
|
/// they are created.
|
|
///
|
|
~AP_Var(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;
|
|
|
|
/// 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;
|
|
|
|
/// 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);
|
|
|
|
/// Load all variables from EEPROM
|
|
///
|
|
static void load_all(void);
|
|
|
|
private:
|
|
const AP_VarAddress _address;
|
|
const prog_char *_name;
|
|
const AP_VarScope * const _scope;
|
|
AP_Var *_link;
|
|
|
|
/// 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;
|
|
|
|
// 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
|
|
};
|
|
|
|
/// Nestable scopes for variable names.
|
|
///
|
|
/// This provides a mechanism for scoping variable names and their
|
|
/// EEPROM addresses.
|
|
///
|
|
/// When AP_Var is asked for the name of a variable, it will
|
|
/// prepend the names of all enclosing scopes. This provides a way
|
|
/// of grouping variables and saving memory when many share a large
|
|
/// common prefix.
|
|
///
|
|
/// When AP_var computes the address of a variable, it will take
|
|
/// into account the address offsets of each of the variable's
|
|
/// enclosing scopes.
|
|
///
|
|
class AP_VarScope
|
|
{
|
|
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)
|
|
{
|
|
}
|
|
|
|
/// 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;
|
|
|
|
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
|
|
};
|
|
|
|
|
|
/// Template class for scalar variables.
|
|
///
|
|
/// Objects of this type have a value, and can be treated in many ways as though they
|
|
/// were the value.
|
|
///
|
|
/// @tparam T The scalar type of the variable
|
|
///
|
|
template<typename T>
|
|
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>(T initialValue = 0,
|
|
AP_VarAddress address = AP_VarNoAddress,
|
|
const prog_char *name = NULL,
|
|
AP_VarScope *scope = NULL) :
|
|
AP_Var(address, name, scope),
|
|
_value(initialValue)
|
|
{
|
|
}
|
|
|
|
// 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);
|
|
}
|
|
|
|
/// Value getter
|
|
///
|
|
T get(void) const { return _value; }
|
|
|
|
/// 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; }
|
|
|
|
private:
|
|
T _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
|
|
|
|
/// Some convenient constant AP_Vars.
|
|
extern const AP_Float AP_FloatUnity;
|
|
extern const AP_Float AP_FloatNegativeUnity;
|
|
extern const AP_Float AP_FloatZero;
|
|
|
|
#endif // AP_Var_H
|