From 4c4274e7c3ab2392d2f09f8ee7439f31d7b3bbbd Mon Sep 17 00:00:00 2001 From: "james.goppert" Date: Mon, 27 Dec 2010 04:11:00 +0000 Subject: [PATCH] Fixed comment style for doxygen. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1293 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/AP_EEProm/AP_EEProm.cpp | 3 -- libraries/AP_EEProm/AP_EEProm.h | 76 +++++++++------------------ libraries/AP_RcChannel/AP_RcChannel.h | 2 - 3 files changed, 25 insertions(+), 56 deletions(-) diff --git a/libraries/AP_EEProm/AP_EEProm.cpp b/libraries/AP_EEProm/AP_EEProm.cpp index 33fca0dce2..af94053d60 100644 --- a/libraries/AP_EEProm/AP_EEProm.cpp +++ b/libraries/AP_EEProm/AP_EEProm.cpp @@ -27,7 +27,4 @@ void AP_EEPromRegistry::add(AP_EEPromEntry * entry, uint16_t & id, uint16_t & ad push_back(entry); } -/** - * The global declaration for the eepromRegistry - */ extern AP_EEPromRegistry eepromRegistry(1024); diff --git a/libraries/AP_EEProm/AP_EEProm.h b/libraries/AP_EEProm/AP_EEProm.h index 9bdaf84bbe..9b130ae0b7 100644 --- a/libraries/AP_EEProm/AP_EEProm.h +++ b/libraries/AP_EEProm/AP_EEProm.h @@ -24,83 +24,61 @@ #include #include -/** - * The interface for data entries in the eeprom registry - */ +/// The interface for data entries in the eeprom registry class AP_EEPromEntry { public: - /** - * Pure virtual function for setting the data value as a float. The function must handle the cast to - * the stored variable types. - */ + /// Pure virtual function for setting the data value + /// as a float. The function must handle the cast to + /// the stored variable types. virtual void setEntry(float val) = 0; - /** - * Pure virtual function for getting data as a float. The function must handle the cast from the - * stored variable types. - */ + /// Pure virtual function for getting data as a float. + /// The function must handle the cast from the + /// stored variable types. virtual float getEntry() = 0; - /** - * Pure virtual function for getting entry name. - */ + /// Pure virtual function for getting entry name. virtual const char * getEntryName() = 0; - /** - * Get the id of the variable. - */ + /// Get the id of the variable. virtual uint16_t getEntryId() = 0; - /** - * Get the address of the variable. - */ + /// Get the address of the variable. virtual uint16_t getEntryAddress() = 0; }; -/** - * The main EEProm Registry class. - */ +///The main EEProm Registry class. class AP_EEPromRegistry : public Vector { public: - /** - * Default constructor - */ + /// Default constructor AP_EEPromRegistry(uint16_t 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); private: - uint16_t _newAddress; /** the address for 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 _newAddress; /// the address for the next new variable + uint16_t _newId; /// the id of the next new variable + uint16_t _maxSize; /// the maximum size of the eeprom memory }; -/** - * Global eepromRegistry declaration. - */ +/// Global eepromRegistry declaration. extern AP_EEPromRegistry eepromRegistry; -/** - * The EEProm Variable template class. This class - * implements get/set/save/load etc for the - * abstract template type. - */ +/// The EEProm Variable template class. +/// This class implements get/set/save/load etc for the +/// abstract template type. template class AP_EEPromVar : public AP_EEPromEntry, public AP_Var { public: - /** - * The default constrcutor - */ + /// The default constrcutor AP_EEPromVar(type data = 0, const char * name = "", bool sync=false) : AP_Var(data,name,sync) { @@ -111,19 +89,15 @@ public: virtual float getEntry() { return this->getAsFloat(); } 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; } - /** - * Get the address of the variable. - */ + /// Get the address of the variable. virtual uint16_t getEntryAddress() { return _address; } private: - uint16_t _id; /** Variable identifier */ - uint16_t _address; /** EEProm address of variable */ + uint16_t _id; /// Variable identifier + uint16_t _address; /// EEProm address of variable }; #endif diff --git a/libraries/AP_RcChannel/AP_RcChannel.h b/libraries/AP_RcChannel/AP_RcChannel.h index 28cced6f0a..11741fb980 100644 --- a/libraries/AP_RcChannel/AP_RcChannel.h +++ b/libraries/AP_RcChannel/AP_RcChannel.h @@ -12,13 +12,11 @@ /// @class AP_RcChannel /// @brief Object managing one RC channel -// class AP_RcChannel{ public: /// Constructor - /// AP_RcChannel(const APM_RC_Class & rc, const uint16_t & ch, const float & scale, const uint16_t & pwmMin, const uint16_t & pwmNeutral, const uint16_t & pwmMax, const uint16_t & pwmDeadZone,