Fixed comment style for doxygen.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1293 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
james.goppert 2010-12-27 04:11:00 +00:00
parent 3e89e3639a
commit 4c4274e7c3
3 changed files with 25 additions and 56 deletions

View File

@ -27,7 +27,4 @@ void AP_EEPromRegistry::add(AP_EEPromEntry * entry, uint16_t & id, uint16_t & ad
push_back(entry); push_back(entry);
} }
/**
* The global declaration for the eepromRegistry
*/
extern AP_EEPromRegistry eepromRegistry(1024); extern AP_EEPromRegistry eepromRegistry(1024);

View File

@ -24,83 +24,61 @@
#include <avr/eeprom.h> #include <avr/eeprom.h>
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
/** /// The interface for data entries in the eeprom registry
* The interface for data entries in the eeprom registry
*/
class AP_EEPromEntry class AP_EEPromEntry
{ {
public: public:
/** /// Pure virtual function for setting the data value
* Pure virtual function for setting the data value as a float. The function must handle the cast to /// as a float. The function must handle the cast to
* the stored variable types. /// the stored variable types.
*/
virtual void setEntry(float val) = 0; virtual void setEntry(float val) = 0;
/** /// Pure virtual function for getting data as a float.
* Pure virtual function for getting data as a float. The function must handle the cast from the /// The function must handle the cast from the
* stored variable types. /// stored variable types.
*/
virtual float getEntry() = 0; virtual float getEntry() = 0;
/** /// Pure virtual function for getting entry name.
* Pure virtual function for getting entry name.
*/
virtual const char * getEntryName() = 0; virtual const char * getEntryName() = 0;
/** /// Get the id of the variable.
* Get the id of the variable.
*/
virtual uint16_t getEntryId() = 0; virtual uint16_t getEntryId() = 0;
/** /// Get the address of the variable.
* Get the address of the variable.
*/
virtual uint16_t getEntryAddress() = 0; virtual uint16_t getEntryAddress() = 0;
}; };
/** ///The main EEProm Registry class.
* The main EEProm Registry class.
*/
class AP_EEPromRegistry : public Vector<AP_EEPromEntry *> class AP_EEPromRegistry : public Vector<AP_EEPromEntry *>
{ {
public: public:
/** /// Default constructor
* Default constructor
*/
AP_EEPromRegistry(uint16_t maxSize) : AP_EEPromRegistry(uint16_t maxSize) :
_newAddress(0), _newId(0), _maxSize(maxSize) _newAddress(0), _newId(0), _maxSize(maxSize)
{ {
} }
/** /// Add an entry to the registry
* Add an entry to the registry
*/
void add(AP_EEPromEntry * entry, uint16_t & id, uint16_t & address, size_t size); void add(AP_EEPromEntry * entry, uint16_t & id, uint16_t & address, size_t size);
private: private:
uint16_t _newAddress; /** the address for the next new variable*/ uint16_t _newAddress; /// the address for the next new variable
uint16_t _newId; /** the id of the next new variable*/ uint16_t _newId; /// the id of the next new variable
uint16_t _maxSize; /** the maximum size of the eeprom memory*/ uint16_t _maxSize; /// the maximum size of the eeprom memory
}; };
/** /// Global eepromRegistry declaration.
* Global eepromRegistry declaration.
*/
extern AP_EEPromRegistry eepromRegistry; extern AP_EEPromRegistry eepromRegistry;
/** /// The EEProm Variable template class.
* The EEProm Variable template class. This class /// This class implements get/set/save/load etc for the
* implements get/set/save/load etc for the /// abstract template type.
* abstract template type.
*/
template <class type> template <class type>
class AP_EEPromVar : public AP_EEPromEntry, public AP_Var<type> class AP_EEPromVar : public AP_EEPromEntry, public AP_Var<type>
{ {
public: public:
/** /// The default constrcutor
* The default constrcutor
*/
AP_EEPromVar(type data = 0, const char * name = "", bool sync=false) : AP_EEPromVar(type data = 0, const char * name = "", bool sync=false) :
AP_Var<type>(data,name,sync) AP_Var<type>(data,name,sync)
{ {
@ -111,19 +89,15 @@ public:
virtual float getEntry() { return this->getAsFloat(); } virtual float getEntry() { return this->getAsFloat(); }
virtual const char * getEntryName() { return this->getName(); } virtual const char * getEntryName() { return this->getName(); }
/** /// Get the id of the variable.
* Get the id of the variable.
*/
virtual uint16_t getEntryId() { return _id; } virtual uint16_t getEntryId() { return _id; }
/** /// Get the address of the variable.
* Get the address of the variable.
*/
virtual uint16_t getEntryAddress() { return _address; } virtual uint16_t getEntryAddress() { return _address; }
private: private:
uint16_t _id; /** Variable identifier */ uint16_t _id; /// Variable identifier
uint16_t _address; /** EEProm address of variable */ uint16_t _address; /// EEProm address of variable
}; };
#endif #endif

View File

@ -12,13 +12,11 @@
/// @class AP_RcChannel /// @class AP_RcChannel
/// @brief Object managing one RC channel /// @brief Object managing one RC channel
//
class AP_RcChannel{ class AP_RcChannel{
public: public:
/// Constructor /// Constructor
///
AP_RcChannel(const APM_RC_Class & rc, const uint16_t & ch, AP_RcChannel(const APM_RC_Class & rc, const uint16_t & ch,
const float & scale, const uint16_t & pwmMin, const uint16_t & pwmNeutral, const float & scale, const uint16_t & pwmMin, const uint16_t & pwmNeutral,
const uint16_t & pwmMax, const uint16_t & pwmDeadZone, const uint16_t & pwmMax, const uint16_t & pwmDeadZone,