mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Following discussions with James, a complete rewrite of AP_Var.
The overriding principle here is to keep the use of AP_Vars as simple as possible, whilst letting the implementation do useful things behind the scenes. To that end, we define AP_Float, AP_Int8, AP_Int16 and AP_Int32. These are strongly typed, so that there is no ambiguity about what a variable "really" is. The classes behave like the variables they are storing; you can use an AP_Float in most places you would use a regular float; you can add to it, multiply by it, etc. If it has been given an address in EEPROM you can load and save it. Variables can be given names, and if they are named then they can be looked up. This allows e.g. a GCS or a test tool to find and traffic in variables that it may not explicitly know about. AP_Var does not attempt to solve the problem of EEPROM address space management. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1399 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
95baa14ecd
commit
76dd412f7d
171
libraries/AP_Common/AP_MetaClass.h
Normal file
171
libraries/AP_Common/AP_MetaClass.h
Normal file
@ -0,0 +1,171 @@
|
||||
// -*- 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.
|
||||
//
|
||||
|
||||
/// @file AP_MetaClass.h
|
||||
/// Abstract meta-class from which other AP classes may inherit.
|
||||
/// Provides type introspection and some basic protocols that can
|
||||
/// be implemented by subclasses.
|
||||
|
||||
#ifndef AP_METACLASS_H
|
||||
#define AP_METACLASS_H
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
/// 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
|
||||
{
|
||||
public:
|
||||
/// Type code, unique to all instances of a given subclass.
|
||||
typedef uint16_t AP_TypeID;
|
||||
|
||||
/// Obtain a value unique to all instances of a specific subclass.
|
||||
///
|
||||
/// 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.
|
||||
///
|
||||
/// As the value is derived from the vtable address, it cannot be
|
||||
/// introspected outside the current state of the system.
|
||||
///
|
||||
/// @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;
|
||||
}
|
||||
|
||||
/// External handle, contains enough information to validate a pointer
|
||||
/// when passed back from an untrusted source.
|
||||
typedef uint32_t AP_MetaHandle;
|
||||
|
||||
/// 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;
|
||||
}
|
||||
|
||||
/// 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
|
||||
|
||||
// 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)
|
||||
return NULL;
|
||||
|
||||
// Compare the type of the object that candidate points to (or garbage if it doesn't)
|
||||
// with .
|
||||
if (candidate->meta_type_id() == id) // compare claimed type with object type
|
||||
return candidate;
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/// Tests whether two objects are of precisely the same class.
|
||||
///
|
||||
/// Note that for p2 inheriting from p1, this will return false.
|
||||
/// Even with RTTI not disabled, there does not seem to be enough information
|
||||
/// to determine whether one class inherits from another.
|
||||
///
|
||||
/// @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();
|
||||
}
|
||||
|
||||
/// Cast an object to an expected class type.
|
||||
///
|
||||
/// This should be used with caution, as _typename's default constructor 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<typename T>
|
||||
static T* meta_cast(AP_MetaClass *p) {
|
||||
T tmp;
|
||||
if (meta_type_equivalent(p, &tmp))
|
||||
return (T *)p;
|
||||
return NULL;
|
||||
}
|
||||
//#define meta_cast(_p, _typename) { _typename _obj; AP_MetaClass::meta_type_equivalent(_p, &_obj) ? (_typename *)_p : NULL; }
|
||||
|
||||
/// Serialise the class.
|
||||
///
|
||||
/// Serialisation 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 serialised 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 serialisation.
|
||||
///
|
||||
virtual size_t serialize(void *buf, size_t bufSize) const { return 0; }
|
||||
|
||||
/// Unserialise the class.
|
||||
///
|
||||
/// Unserialising a class from a buffer into which the class previously serialised
|
||||
/// itself restores the instance to an identical state, where "identical" may be
|
||||
/// defined in context.
|
||||
///
|
||||
/// Classes that wrap variables should define the format of their serialised data so
|
||||
/// that external providers can reliably encode it.
|
||||
///
|
||||
/// @param buf Buffer containing serialised data.
|
||||
/// @param bufSize The size of the buffer.
|
||||
/// @return The number of bytes from the buffer that would be consumed
|
||||
/// unserialising the data. If the value is less than or equal
|
||||
/// to bufSize, unserialisation 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) { return false; }
|
||||
};
|
||||
|
||||
#endif // AP_METACLASS_H
|
@ -11,5 +11,70 @@
|
||||
|
||||
#include "AP_Var.h"
|
||||
|
||||
AP_Int8 AP_unity(1);
|
||||
AP_Int8 AP_negativeUnity(-1);
|
||||
const AP_Float AP_GainUnity(1.0);
|
||||
const AP_Float AP_GainNegativeUnity(-1.0);
|
||||
const AP_Float AP_Zero(0);
|
||||
|
||||
//
|
||||
// Lookup interface for variables.
|
||||
//
|
||||
AP_VarBase *AP_VarBase::_variables = NULL;
|
||||
AP_VarBase *AP_VarBase::_lookupHint = NULL;
|
||||
int AP_VarBase::_lookupHintIndex = 0;
|
||||
|
||||
AP_VarBase *
|
||||
AP_VarBase::lookup(int index)
|
||||
{
|
||||
AP_VarBase *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
|
||||
|
||||
p = _lookupHint; // start at the hint point
|
||||
i = index - _lookupHintIndex; // count only the distance from the hint to the index
|
||||
} else {
|
||||
|
||||
p = _variables; // start at the beginning of the list
|
||||
i = index; // count to the index
|
||||
}
|
||||
|
||||
// search
|
||||
while (index-- && p) // count until we hit the index or the end of the list
|
||||
p = p->_link;
|
||||
|
||||
// update the cache on hit
|
||||
if (p) {
|
||||
_lookupHintIndex = i;
|
||||
_lookupHint = p;
|
||||
}
|
||||
|
||||
return(p);
|
||||
}
|
||||
|
||||
// Save all variables that have an identity.
|
||||
//
|
||||
void
|
||||
AP_VarBase::save_all(void)
|
||||
{
|
||||
AP_VarBase *p = _variables;
|
||||
|
||||
while (p) {
|
||||
p->save();
|
||||
p = p->_link;
|
||||
}
|
||||
}
|
||||
|
||||
// Load all variables that have an identity.
|
||||
//
|
||||
void
|
||||
AP_VarBase::load_all(void)
|
||||
{
|
||||
AP_VarBase *p = _variables;
|
||||
|
||||
while (p) {
|
||||
p->load();
|
||||
p = p->_link;
|
||||
}
|
||||
}
|
||||
|
@ -13,145 +13,311 @@
|
||||
#define AP_Var_H
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <string.h>
|
||||
#include <stdint.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include <avr/eeprom.h>
|
||||
|
||||
class AP_VarI
|
||||
#include <AP_MetaClass.h>
|
||||
|
||||
/// Nestable scopes for variable names.
|
||||
///
|
||||
/// This provides a mechanism for scoping variable names, and
|
||||
/// may later be extended for other purposes.
|
||||
///
|
||||
/// When AP_VarBase 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.
|
||||
///
|
||||
class AP_VarScope
|
||||
{
|
||||
public:
|
||||
/// Constructor
|
||||
///
|
||||
/// @param scopeName The name of the scope.
|
||||
///
|
||||
AP_VarScope(const prog_char *name,
|
||||
AP_VarScope *parent = NULL) :
|
||||
_name(name),
|
||||
_parent(parent)
|
||||
{
|
||||
}
|
||||
|
||||
/// Set the variable value as a float
|
||||
virtual void setF(const float & val) = 0;
|
||||
/// 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);
|
||||
}
|
||||
|
||||
/// Get the variable value as a float
|
||||
virtual const float getF() = 0;
|
||||
|
||||
/// Set the variable value as an int16
|
||||
virtual void setI(const int16_t & val) = 0;
|
||||
|
||||
/// Get the variable value as an int16
|
||||
virtual const int16_t getI() = 0;
|
||||
|
||||
/// Set the variable value as a bool
|
||||
virtual void setB(const bool & val) = 0;
|
||||
|
||||
/// Get the variable value as an bool
|
||||
virtual const bool getB() = 0;
|
||||
|
||||
/// Save a variable to eeprom
|
||||
virtual void save() = 0;
|
||||
|
||||
/// Load a variable from eeprom
|
||||
virtual void load() = 0;
|
||||
|
||||
/// Get the name. This is useful for ground stations.
|
||||
virtual const char * getName() = 0;
|
||||
|
||||
/// If sync is true the a load will always occure before a get and a save will always
|
||||
/// occure before a set.
|
||||
virtual const bool & getSync() = 0;
|
||||
|
||||
/// Set the sync property
|
||||
virtual void setSync(const bool & sync) = 0;
|
||||
private:
|
||||
const prog_char *_name; /// pointer to the scope name in program memory
|
||||
AP_VarScope *_parent; /// pointer to a parent scope, if one exists
|
||||
};
|
||||
|
||||
/// The variable template class. This class
|
||||
/// implements get/set/save/load etc for the
|
||||
/// abstract template type.
|
||||
template <class type>
|
||||
class AP_Var : public AP_VarI
|
||||
/// Base class for variables.
|
||||
///
|
||||
/// Provides naming and lookup services for variables.
|
||||
///
|
||||
class AP_VarBase : public AP_MetaClass
|
||||
{
|
||||
public:
|
||||
/// The default constrcutor
|
||||
AP_Var(const type & data, const char * name = "", const char * parentName = "", const bool & sync=false) :
|
||||
_data(data), _name(name), _parentName(parentName), _sync(sync)
|
||||
/// A unique identity for variables that can be saved to EEPROM
|
||||
///
|
||||
/// @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_VarIdentity;
|
||||
static const AP_VarIdentity AP_VarUnsaved = 0;
|
||||
|
||||
/// The largest variable that will be saved to EEPROM
|
||||
///
|
||||
static const size_t AP_VarMaxSize = 16;
|
||||
|
||||
/// Constructor
|
||||
///
|
||||
/// @param name An optional name by which the variable may be known.
|
||||
/// @param scope An optional scope that the variable may be a contained within.
|
||||
///
|
||||
AP_VarBase(AP_VarIdentity identity = AP_VarUnsaved,
|
||||
const prog_char *name = NULL,
|
||||
AP_VarScope *scope = NULL) :
|
||||
_identity(identity),
|
||||
_name(name),
|
||||
_scope(scope)
|
||||
{
|
||||
if (name) {
|
||||
_link = _variables;
|
||||
_variables = this;
|
||||
}
|
||||
}
|
||||
|
||||
/// float copy constructor
|
||||
AP_Var(AP_VarI & v)
|
||||
{
|
||||
setF(v.getF());
|
||||
/// Copy the variable name, prefixed by any parent class 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 (_scope)
|
||||
_scope->copy_name(buffer, bufferSize);
|
||||
strlcat_P(buffer, _name, bufferSize);
|
||||
}
|
||||
|
||||
/// Set the variable value
|
||||
void set(const type & val) {
|
||||
_data = val;
|
||||
if (_sync) save();
|
||||
/// Return a pointer to the n'th known variable
|
||||
///
|
||||
/// This interface is designed for the use of relatively low-rate clients;
|
||||
/// GCS interfaces in particular. It may implement an acceleration scheme
|
||||
/// for optimising the lookup of parameters.
|
||||
///
|
||||
/// 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_VarBase *lookup(int index);
|
||||
|
||||
/// Save the current value of the variable to EEPROM.
|
||||
///
|
||||
/// This interface works for any subclass that implements
|
||||
/// serialize.
|
||||
///
|
||||
void save(void) {
|
||||
if (_identity != AP_VarUnsaved) {
|
||||
uint8_t vbuf[AP_VarMaxSize];
|
||||
size_t size;
|
||||
|
||||
// serialise 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 *)_identity, size);
|
||||
}
|
||||
}
|
||||
|
||||
/// Get the variable value.
|
||||
const type & get() {
|
||||
if (_sync) load();
|
||||
return _data;
|
||||
/// Load the variable from EEPROM.
|
||||
///
|
||||
/// This interface works for any subclass that implements
|
||||
/// unserialize.
|
||||
///
|
||||
void load(void) {
|
||||
if (_identity != AP_VarUnsaved) {
|
||||
uint8_t vbuf[AP_VarMaxSize];
|
||||
size_t size;
|
||||
|
||||
// ask the unserialiser how big the variable is
|
||||
size = unserialize(NULL, 0);
|
||||
|
||||
// read the buffer from EEPROM
|
||||
if (size <= sizeof(vbuf)) {
|
||||
eeprom_read_block(vbuf, (void *)_identity, size);
|
||||
unserialize(vbuf, size);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/// Set the variable value as a float
|
||||
virtual void setF(const float & val) {
|
||||
set(val);
|
||||
}
|
||||
/// Save all variables to EEPROM
|
||||
///
|
||||
static void save_all(void);
|
||||
|
||||
/// Get the variable as a float
|
||||
virtual const float getF() {
|
||||
return get();
|
||||
}
|
||||
/// Load all variables from EEPROM
|
||||
///
|
||||
static void load_all(void);
|
||||
|
||||
/// Set the variable value as an Int16
|
||||
virtual void setI(const int16_t & val) {
|
||||
set(val);
|
||||
}
|
||||
private:
|
||||
const AP_VarIdentity _identity;
|
||||
const prog_char *_name;
|
||||
AP_VarScope *_scope;
|
||||
AP_VarBase *_link;
|
||||
|
||||
/// Get the variable value as an Int16
|
||||
virtual const int16_t getI() {
|
||||
return get();
|
||||
}
|
||||
|
||||
/// Set the variable value as an Int16
|
||||
virtual void setB(const bool & val) {
|
||||
set(val);
|
||||
}
|
||||
|
||||
/// Get the variable value as an Int16
|
||||
virtual const bool getB() {
|
||||
return get();
|
||||
}
|
||||
|
||||
/// Save a variable to eeprom
|
||||
virtual void save()
|
||||
{
|
||||
}
|
||||
|
||||
/// Load a variable from eeprom
|
||||
virtual void load()
|
||||
{
|
||||
}
|
||||
|
||||
/// Get the name. This is useful for ground stations.
|
||||
virtual const char * getName() { return _name; }
|
||||
|
||||
/// Get the parent name. This is also useful for ground stations.
|
||||
virtual const char * getParentName() { return _parentName; }
|
||||
|
||||
/// If sync is true the a load will always occure before a get and a save will always
|
||||
/// occure before a set.
|
||||
virtual const bool & getSync() { return _sync; }
|
||||
virtual void setSync(const bool & sync) { _sync = sync; }
|
||||
|
||||
protected:
|
||||
type _data; /// The data that is stored on the heap */
|
||||
const char * _name; /// The variable name, useful for gcs and terminal output
|
||||
const char * _parentName; /// The variable parent name, useful for gcs and terminal output
|
||||
bool _sync; /// Whether or not to call save/load on get/set
|
||||
// static state used by ::lookup
|
||||
static AP_VarBase *_variables;
|
||||
static AP_VarBase *_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
|
||||
};
|
||||
|
||||
typedef AP_Var<float> AP_Float;
|
||||
typedef AP_Var<int8_t> AP_Int8;
|
||||
typedef AP_Var<uint8_t> AP_Uint8;
|
||||
typedef AP_Var<int16_t> AP_Int16;
|
||||
typedef AP_Var<uint16_t> AP_Uint16;
|
||||
typedef AP_Var<int32_t> AP_Int32;
|
||||
typedef AP_Var<uint32_t> AP_Unt32;
|
||||
typedef AP_Var<bool> AP_Bool;
|
||||
|
||||
extern AP_Int8 AP_unity;
|
||||
extern AP_Int8 AP_negativeUnity;
|
||||
/// 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_Var : public AP_VarBase
|
||||
{
|
||||
public:
|
||||
/// Constructor
|
||||
///
|
||||
/// @note Constructors for AP_Var are specialised so that they can
|
||||
/// pass the correct typeCode argument to the AP_VarBase 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_Var<T>(T initialValue = 0,
|
||||
AP_VarIdentity identity = AP_VarUnsaved,
|
||||
const prog_char *name = NULL,
|
||||
AP_VarScope *scope = NULL) :
|
||||
AP_VarBase(identity, name, scope),
|
||||
_value(initialValue)
|
||||
{
|
||||
}
|
||||
|
||||
// Serialise _value into the buffer, but only if it is big enough.
|
||||
///
|
||||
virtual size_t serialise(void *buf, size_t size) {
|
||||
if (size >= sizeof(T))
|
||||
*(T *)buf = _value;
|
||||
return sizeof(T);
|
||||
}
|
||||
|
||||
// Unserialise from the buffer, but only if it is big enough.
|
||||
//
|
||||
virtual size_t unserialise(void *buf, size_t size) {
|
||||
if (size >= sizeof(T))
|
||||
_value = *(T*)buf;
|
||||
return sizeof(T);
|
||||
}
|
||||
|
||||
/// Value getter
|
||||
///
|
||||
T get(void) { return _value; }
|
||||
|
||||
/// Value setter
|
||||
///
|
||||
void set(T v) { _value = v; }
|
||||
|
||||
/// Conversion to T returns a reference to the value, may lead to simpler
|
||||
/// code than the getter/setter in some cases.
|
||||
///
|
||||
operator T&() { return _value; }
|
||||
|
||||
/// Conversion to a pointer to T returns a pointer to the value,
|
||||
/// permits passing the value by reference.
|
||||
///
|
||||
operator T*() const { return &_value; }
|
||||
|
||||
// Assignment from any value that T is compatible with.
|
||||
T operator = (const T v) const { return (_value = v); }
|
||||
|
||||
// Comparison with any value that T is compatible with (should be avoided for T == float)
|
||||
bool operator == (const T &v) const { return _value == v; }
|
||||
bool operator != (const T &v) const { return _value != v; }
|
||||
|
||||
// Negation
|
||||
T operator - (void) const { return -_value; }
|
||||
|
||||
// Addition
|
||||
T operator + (const T &v) const { return _value + v; }
|
||||
T operator += (const T &v) { return (_value += v); }
|
||||
|
||||
// Subtraction
|
||||
T operator - (const T &v) const { return _value - v; }
|
||||
T operator -= (const T &v) { return (_value -= v); }
|
||||
|
||||
// Multiplication
|
||||
T operator * (const T &v) const { return _value * v; }
|
||||
T operator *= (const T &v) { return (_value *= v); }
|
||||
|
||||
// Division
|
||||
T operator / (const T &v) const { return _value / v; }
|
||||
T operator /= (const T &v) { return (_value /= v); }
|
||||
|
||||
// Modulus
|
||||
T operator % (const T &v) const { return _value % v; }
|
||||
T operator %= (const T &v) { return (_value %= v); }
|
||||
|
||||
// Bitwise operations
|
||||
T operator & (const T &v) const { return _value & v; }
|
||||
T operator &= (const T &v) { return (_value &= v); }
|
||||
T operator | (const T &v) const { return _value | v; }
|
||||
T operator |= (const T &v) { return (_value |= v); }
|
||||
T operator ^ (const T &v) const { return _value ^ v; }
|
||||
T operator ^= (const T &v) { return (_value ^= v); }
|
||||
T operator << (const T &v) const { return _value << v; }
|
||||
T operator <<= (const T &v) { return (_value <<= v); }
|
||||
T operator >> (const T &v) const { return _value >> v; }
|
||||
T operator >>= (const T &v) { return (_value >>= v); }
|
||||
|
||||
private:
|
||||
T _value;
|
||||
};
|
||||
|
||||
|
||||
/// Convenience macro for defining instances of the AP_Var template
|
||||
///
|
||||
#define AP_VARDEF(_t, _n) \
|
||||
typedef AP_Var<_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
|
||||
|
66
libraries/AP_Common/examples/AP_Var/AP_Var.pde
Normal file
66
libraries/AP_Common/examples/AP_Var/AP_Var.pde
Normal file
@ -0,0 +1,66 @@
|
||||
//
|
||||
// Unit tests for the AP_MetaClass and AP_Var classes.
|
||||
//
|
||||
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
|
||||
FastSerialPort(Serial, 0);
|
||||
|
||||
#define TEST(name) Serial.println("test: " #name)
|
||||
#define REQUIRE(expr) if (!(expr)) Serial.println("FAIL: " #expr)
|
||||
|
||||
void
|
||||
setup(void)
|
||||
{
|
||||
Serial.begin(38400);
|
||||
|
||||
// MetaClass: test type ID
|
||||
{
|
||||
TEST(meta_type_id);
|
||||
|
||||
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();
|
||||
|
||||
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));
|
||||
}
|
||||
|
||||
// MetaClass: test external handles
|
||||
{
|
||||
TEST(meta_handle);
|
||||
|
||||
AP_Float f;
|
||||
AP_MetaClass::AP_MetaHandle 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));
|
||||
}
|
||||
|
||||
// MetaClass: casting
|
||||
{
|
||||
TEST(meta_cast);
|
||||
|
||||
AP_Float f;
|
||||
|
||||
REQUIRE(NULL != AP_MetaClass::meta_cast<AP_Float>(&f));
|
||||
REQUIRE(NULL == AP_MetaClass::meta_cast<AP_Int8>(&f));
|
||||
}
|
||||
|
||||
Serial.println("done.");
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
loop(void)
|
||||
{
|
||||
}
|
2
libraries/AP_Common/examples/AP_Var/Makefile
Normal file
2
libraries/AP_Common/examples/AP_Var/Makefile
Normal file
@ -0,0 +1,2 @@
|
||||
BOARD = mega
|
||||
include ../../Arduino.mk
|
Loading…
Reference in New Issue
Block a user