mirror of https://github.com/ArduPilot/ardupilot
Fixed include problem in AP_RcChannel.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1316 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
09b02a06fd
commit
34ed0b8183
|
@ -83,84 +83,93 @@ struct Location {
|
|||
int32_t lng; ///< param 4 - Longitude * 10**7
|
||||
};
|
||||
|
||||
/**
|
||||
* The parameter template class. This class
|
||||
* implements get/set/save/load etc for the
|
||||
* abstract template type.
|
||||
*/
|
||||
template <class type>
|
||||
class AP_Var
|
||||
/// The AP variable interface. This allows different types
|
||||
/// of variables to be passed to blocks for floating point
|
||||
/// math, memory management, etc.
|
||||
class AP_VarI
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* The default constrcutor
|
||||
*/
|
||||
|
||||
/// Set the variable value as a float
|
||||
virtual void setF(const float & val) = 0;
|
||||
|
||||
/// Get the variable as a float
|
||||
virtual const float & getF() = 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(bool sync) = 0;
|
||||
};
|
||||
|
||||
/// 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
|
||||
{
|
||||
public:
|
||||
/// The default constrcutor
|
||||
AP_Var(const type & data, const char * name = "", const bool & sync=false) :
|
||||
_data(data), _name(name), _sync(sync)
|
||||
{
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the variable value
|
||||
*/
|
||||
void set(const type & val) {
|
||||
/// Set the variable value
|
||||
virtual void set(const type & val) {
|
||||
_data = val;
|
||||
if (_sync) save();
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the variable value.
|
||||
*/
|
||||
const type & get() {
|
||||
/// Get the variable value.
|
||||
virtual const type & get() {
|
||||
if (_sync) load();
|
||||
return _data;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the variable value as a float
|
||||
*/
|
||||
void setAsFloat(const float & val) {
|
||||
/// Set the variable value as a float
|
||||
virtual void setF(const float & val) {
|
||||
set(val);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the variable as a float
|
||||
*/
|
||||
const float & getAsFloat() {
|
||||
/// Get the variable as a float
|
||||
virtual const float & getF() {
|
||||
return get();
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Save a variable to eeprom
|
||||
*/
|
||||
/// Save a variable to eeprom
|
||||
virtual void save()
|
||||
{
|
||||
}
|
||||
|
||||
/**
|
||||
* Load a variable from eeprom
|
||||
*/
|
||||
/// Load a variable from eeprom
|
||||
virtual void load()
|
||||
{
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the name. This is useful for ground stations.
|
||||
*/
|
||||
const char * getName() { return _name; }
|
||||
/// Get the name. This is useful for ground stations.
|
||||
virtual const char * getName() { return _name; }
|
||||
|
||||
/**
|
||||
* If sync is true the a load will always occure before a get and a save will always
|
||||
* occure before a set.
|
||||
*/
|
||||
const bool & getSync() { return _sync; }
|
||||
void setSync(bool sync) { _sync = sync; }
|
||||
/// 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(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 */
|
||||
bool _sync; /** Whether or not to call save/load on get/set */
|
||||
type _data; /// The data that is stored on the heap */
|
||||
const char * _name; /// The variable name, useful for gcs and terminal output
|
||||
bool _sync; /// Whether or not to call save/load on get/set
|
||||
};
|
||||
|
||||
//@}
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
|
||||
#include <AP_EEProm.h>
|
||||
|
||||
void AP_EEPromRegistry::add(AP_EEPromEntry * entry, uint16_t & id, uint16_t & address, size_t size)
|
||||
void AP_EEPromRegistry::add(AP_EEPromEntryI * entry, uint16_t & id, uint16_t & address, size_t size)
|
||||
{
|
||||
if (_newAddress + size > _maxSize) return;
|
||||
address = _newAddress;
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#include <avr/pgmspace.h>
|
||||
|
||||
/// The interface for data entries in the eeprom registry
|
||||
class AP_EEPromEntry
|
||||
class AP_EEPromEntryI
|
||||
{
|
||||
public:
|
||||
/// Pure virtual function for setting the data value
|
||||
|
@ -49,7 +49,7 @@ public:
|
|||
};
|
||||
|
||||
///The main EEProm Registry class.
|
||||
class AP_EEPromRegistry : public Vector<AP_EEPromEntry *>
|
||||
class AP_EEPromRegistry : public Vector<AP_EEPromEntryI *>
|
||||
{
|
||||
public:
|
||||
|
||||
|
@ -60,7 +60,7 @@ public:
|
|||
}
|
||||
|
||||
/// Add an entry to the registry
|
||||
void add(AP_EEPromEntry * entry, uint16_t & id, uint16_t & address, size_t size);
|
||||
void add(AP_EEPromEntryI * entry, uint16_t & id, uint16_t & address, size_t size);
|
||||
|
||||
private:
|
||||
uint16_t _newAddress; /// the address for the next new variable
|
||||
|
@ -75,7 +75,7 @@ extern AP_EEPromRegistry eepromRegistry;
|
|||
/// This class implements get/set/save/load etc for the
|
||||
/// abstract template type.
|
||||
template <class type>
|
||||
class AP_EEPromVar : public AP_EEPromEntry, public AP_Var<type>
|
||||
class AP_EEPromVar : public AP_EEPromEntryI, public AP_Var<type>
|
||||
{
|
||||
public:
|
||||
/// The default constrcutor
|
||||
|
@ -85,8 +85,8 @@ public:
|
|||
eepromRegistry.add(this,_id,_address,sizeof(type));
|
||||
}
|
||||
|
||||
virtual void setEntry(float val) { this->setAsFloat(val); }
|
||||
virtual float getEntry() { return this->getAsFloat(); }
|
||||
virtual void setEntry(float val) { this->setF(val); }
|
||||
virtual float getEntry() { return this->getF(); }
|
||||
virtual const char * getEntryName() { return this->getName(); }
|
||||
|
||||
/// Get the id of the variable.
|
||||
|
|
|
@ -9,6 +9,7 @@
|
|||
#include <AP_Common.h>
|
||||
#include <AP_RcChannel.h> // ArduPilot Mega RC Library
|
||||
#include <AP_EEProm.h>
|
||||
#include <APM_RC.h>
|
||||
|
||||
AP_EEPromVar<float> scale(45.0,"RC1_SCALE");
|
||||
AP_EEPromVar<uint16_t> pwmMin(1000,"RC1_PWMMIN");
|
||||
|
|
Loading…
Reference in New Issue