From 13e75a39e3bae9f65ced7ed6c29799d097bc6be6 Mon Sep 17 00:00:00 2001 From: fjrodl Date: Tue, 29 Oct 2024 14:07:43 +0100 Subject: [PATCH 1/9] Comments in the code to improve readability --- README.md | 18 +++ .../include/cs4home_core/Afferent.hpp | 70 +++++++++-- .../include/cs4home_core/CognitiveModule.hpp | 80 +++++++++--- cs4home_core/include/cs4home_core/Core.hpp | 40 +++++- .../include/cs4home_core/Coupling.hpp | 15 ++- .../include/cs4home_core/Efferent.hpp | 33 ++++- cs4home_core/include/cs4home_core/Flow.hpp | 25 +++- cs4home_core/include/cs4home_core/Master.hpp | 50 +++++++- cs4home_core/include/cs4home_core/Meta.hpp | 16 ++- cs4home_core/include/cs4home_core/macros.hpp | 11 +- cs4home_core/src/cs4home_core/Afferent.cpp | 26 ++++ .../src/cs4home_core/CognitiveModule.cpp | 90 +++++++------- cs4home_core/src/cs4home_core/Core.cpp | 8 ++ cs4home_core/src/cs4home_core/Coupling.cpp | 8 ++ cs4home_core/src/cs4home_core/Efferent.cpp | 14 +++ cs4home_core/src/cs4home_core/Flow.cpp | 11 +- cs4home_core/src/cs4home_core/Master.cpp | 38 +++++- cs4home_core/src/cs4home_core/Meta.cpp | 8 ++ cs4home_core/test/DefaultCoupling.cpp | 23 +++- cs4home_core/test/DefaultMeta.cpp | 23 +++- cs4home_core/test/ImageFilter.cpp | 53 +++++++- cs4home_core/test/ImageFilterCB.cpp | 49 +++++++- cs4home_core/test/SimpleImageInput.cpp | 22 +++- cs4home_core/test/SimpleImageOutput.cpp | 26 +++- cs4home_core/test/cognitive_module_test.cpp | 115 ++++++++++++++++-- cs4home_core/test/master_test.cpp | 21 +++- 26 files changed, 767 insertions(+), 126 deletions(-) diff --git a/README.md b/README.md index 6799d18..513db65 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,20 @@ # cs4home_architecture + +This work presents a model for the integration and management of the functional components of a general robotic system, using ROS 2 as a technical foundation. The proposal is inspired by the organization of the human nervous system, developing a management metamodel based on neuroregulatory centers and structured into afferent and efferent components that facilitate information flow and processing within the robotic system. + +The model introduces a service-oriented management approach adapted to the distributed environment of ROS 2. This enables the creation and coordination of functional entities according to principles inspired by the human neuroregulatory system, where afferent components gather and process data from the environment, while efferent components distribute and execute commands, using ROS 2 communication patterns such as publish-subscribe, services, and actions. + +This structure addresses traditional challenges in robotics, such as hardware-business logic coupling, the need for rapid development of robotic systems, and the complexity of incorporating new knowledge and technologies into existing systems. Key features of this model include: + +- Uniform management of system components: Functional elements are managed in a homogeneous way, where each component contributes from a modular and functional perspective. Using ROS 2, interoperability and modular control are achieved, allowing the simplified integration of afferent and efferent components within the system. + +- Metamodel inspired by the human neuroregulatory system: The organization of components follows dynamics similar to the nervous system, using ROS 2 nodes and their lifecycle to manage activations and deactivations. Afferent nodes capture sensory data and external signals, while efferent nodes act on the system based on decisions made, allowing controlled and adaptive responses. + +- Integration of functional entities via ROS 2 technologies: The proposal incorporates ROS 2's publish-subscribe, service, and action techniques for distributed integration of functional entities, facilitating dynamic and adaptable component connections. + +This model is designed as an adaptable solution for a wide variety of robotic systems based on ROS 2, from low-level controls to complex inter-robot coordination and communication. This adaptability allows the scaling and distribution of components across diverse architectures, facilitating the incorporation of new functionalities without the need for redesign. + + +## Examples + Implementation of the architecture from the Social Testbed point of view diff --git a/cs4home_core/include/cs4home_core/Afferent.hpp b/cs4home_core/include/cs4home_core/Afferent.hpp index 4c05712..06e089d 100644 --- a/cs4home_core/include/cs4home_core/Afferent.hpp +++ b/cs4home_core/include/cs4home_core/Afferent.hpp @@ -29,25 +29,69 @@ namespace cs4home_core { +/** + * @class Afferent + * @brief Manages afferent processing in robotic nodes, including message handling, + * subscriptions, and modes for processing serialized data. + */ class Afferent { public: RCLCPP_SMART_PTR_DEFINITIONS(Afferent) + /** + * @enum EfferentProcessMode + * @brief Defines processing modes for serialized message handling. + */ enum EfferentProcessMode {CALLBACK, ONDEMAND}; + /** + * @brief Constructor for the Afferent class. + * @param parent Shared pointer to the lifecycle node managing this instance. + */ explicit Afferent(rclcpp_lifecycle::LifecycleNode::SharedPtr parent); + /** + * @brief Configures the afferent component; intended for subclass implementation. + * @return True if configuration is successful. + */ virtual bool configure() = 0; + /** + * @brief Sets the processing mode and an optional callback function. + * + * @param mode Processing mode for handling messages. + * @param cb Optional callback function for handling serialized messages in CALLBACK mode. + */ void set_mode( EfferentProcessMode mode, std::function)> cb = nullptr); + + /** + * @brief Gets the current processing mode. + * @return The current EfferentProcessMode. + */ EfferentProcessMode get_mode() {return mode_;} + + /** + * @brief Sets the maximum queue size for storing messages. + * @param size Maximum number of messages the queue can hold. + */ void set_max_queue_size(size_t size) {max_queue_size_ = size;} + + /** + * @brief Gets the maximum queue size. + * @return The maximum queue size. + */ size_t get_max_queue_size() {return max_queue_size_;} + /** + * @brief Converts a serialized message to a typed message. + * @tparam MessageT Type of the message to deserialize. + * @param msg Serialized message to convert. + * @return A unique pointer to the deserialized message. + */ template std::unique_ptr get_msg( std::unique_ptr msg) { @@ -58,6 +102,11 @@ class Afferent return std::move(typed_msg); } + /** + * @brief Retrieves the next message from the queue, if available. + * @tparam MessageT Type of message to retrieve. + * @return A unique pointer to the next message, or nullptr if the queue is empty. + */ template std::unique_ptr get_msg() { if (msg_queue_.empty()) { @@ -71,17 +120,24 @@ class Afferent } protected: - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; - std::vector> subs_; + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; /**< Shared pointer to the parent node. */ + std::vector> subs_; /**< List of subscriptions. */ + + EfferentProcessMode mode_ {ONDEMAND}; /**< Current processing mode. */ - EfferentProcessMode mode_ {ONDEMAND}; + const size_t MAX_DEFAULT_QUEUE_SIZE = 100; /**< Default maximum queue size. */ + size_t max_queue_size_ {MAX_DEFAULT_QUEUE_SIZE}; /**< Maximum queue size. */ + std::queue> msg_queue_; /**< Queue for serialized messages. */ - const size_t MAX_DEFAULT_QUEUE_SIZE = 100; - size_t max_queue_size_ {MAX_DEFAULT_QUEUE_SIZE}; - std::queue> msg_queue_; + std::function)> callback_; /**< Callback for serialized messages. */ - std::function)> callback_; + /** + * @brief Creates a subscriber for a specific topic and message type. + * @param topic Topic to subscribe to. + * @param type Type of message for the subscription. + * @return True if the subscriber was created successfully. + */ bool create_subscriber(const std::string & topic, const std::string & type); }; diff --git a/cs4home_core/include/cs4home_core/CognitiveModule.hpp b/cs4home_core/include/cs4home_core/CognitiveModule.hpp index c54173d..f764085 100644 --- a/cs4home_core/include/cs4home_core/CognitiveModule.hpp +++ b/cs4home_core/include/cs4home_core/CognitiveModule.hpp @@ -12,12 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. - #ifndef CS4HOME_CORE__COGNITIVEMODULE_HPP_ #define CS4HOME_CORE__COGNITIVEMODULE_HPP_ #include - #include #include @@ -34,35 +32,85 @@ namespace cs4home_core { +/** + * @class CognitiveModule + * @brief Extends the LifecycleNode to manage cognitive processing components in a ROS 2 lifecycle, + * including afferent, efferent, core, meta, and coupling components. + */ class CognitiveModule : public rclcpp_lifecycle::LifecycleNode { public: RCLCPP_SMART_PTR_DEFINITIONS(CognitiveModule) - using CallbackReturnT = - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; + using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; + /** + * @brief Constructs a CognitiveModule with the specified node options. + * @param options Node options for configuring the lifecycle node. + */ explicit CognitiveModule(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); + /** + * @brief Lifecycle transition callback for configuration. + * @param state The current lifecycle state. + * @return Result of the configuration, typically success or failure. + */ CallbackReturnT on_configure(const rclcpp_lifecycle::State & state); + + /** + * @brief Lifecycle transition callback for activation. + * @param state The current lifecycle state. + * @return Result of the activation, typically success or failure. + */ CallbackReturnT on_activate(const rclcpp_lifecycle::State & state); + + /** + * @brief Lifecycle transition callback for deactivation. + * @param state The current lifecycle state. + * @return Result of the deactivation, typically success or failure. + */ CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state); + + /** + * @brief Lifecycle transition callback for cleanup. + * @param state The current lifecycle state. + * @return Result of the cleanup, typically success or failure. + */ CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state); + + /** + * @brief Lifecycle transition callback for shutdown. + * @param state The current lifecycle state. + * @return Result of the shutdown, typically success or failure. + */ CallbackReturnT on_shutdown(const rclcpp_lifecycle::State & state); + + /** + * @brief Lifecycle transition callback for error handling. + * @param state The current lifecycle state. + * @return Result of the error handling, typically success or failure. + */ CallbackReturnT on_error(const rclcpp_lifecycle::State & state); protected: - Afferent::SharedPtr afferent_; - Efferent::SharedPtr efferent_; - Core::SharedPtr core_; - Meta::SharedPtr meta_; - Coupling::SharedPtr coupling_; - - std::string core_name_; - std::string afferent_name_; - std::string efferent_name_; - std::string meta_name_; - std::string coupling_name_; - + Afferent::SharedPtr afferent_; /**< Pointer to the Afferent component. */ + Efferent::SharedPtr efferent_; /**< Pointer to the Efferent component. */ + Core::SharedPtr core_; /**< Pointer to the Core component. */ + Meta::SharedPtr meta_; /**< Pointer to the Meta component. */ + Coupling::SharedPtr coupling_; /**< Pointer to the Coupling component. */ + + std::string core_name_; /**< Name of the Core component. */ + std::string afferent_name_; /**< Name of the Afferent component. */ + std::string efferent_name_; /**< Name of the Efferent component. */ + std::string meta_name_; /**< Name of the Meta component. */ + std::string coupling_name_; /**< Name of the Coupling component. */ + + /** + * @brief Loads a specified component by name and returns a shared pointer to it. + * @tparam T Type of the component to load. + * @param name Name of the component to load. + * @param parent Shared pointer to the parent lifecycle node. + * @return A tuple containing the loaded component pointer and its name. + */ template std::tuple load_component( const std::string & name, rclcpp_lifecycle::LifecycleNode::SharedPtr parent); diff --git a/cs4home_core/include/cs4home_core/Core.hpp b/cs4home_core/include/cs4home_core/Core.hpp index 3e23af1..0891691 100644 --- a/cs4home_core/include/cs4home_core/Core.hpp +++ b/cs4home_core/include/cs4home_core/Core.hpp @@ -12,13 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. - #ifndef CS4HOME_CORE__CORE_HPP_ #define CS4HOME_CORE__CORE_HPP_ #include - #include "cs4home_core/Afferent.hpp" #include "cs4home_core/Efferent.hpp" @@ -28,24 +26,56 @@ namespace cs4home_core { +/** + * @class Core + * @brief Manages core functionality for a robotic component, including lifecycle transitions + * and connections to afferent and efferent processing components. + */ class Core { public: RCLCPP_SMART_PTR_DEFINITIONS(Core) + /** + * @brief Constructs a Core object associated with a parent lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this Core instance. + */ explicit Core(rclcpp_lifecycle::LifecycleNode::SharedPtr parent); + /** + * @brief Configures the Core component. + * @return True if configuration is successful. + */ virtual bool configure() = 0; + + /** + * @brief Activates the Core component. + * @return True if activation is successful. + */ virtual bool activate() = 0; + + /** + * @brief Deactivates the Core component. + * @return True if deactivation is successful. + */ virtual bool deactivate() = 0; + /** + * @brief Sets the Afferent component associated with this Core. + * @param afferent Shared pointer to an Afferent component. + */ void set_afferent(cs4home_core::Afferent::SharedPtr afferent) {afferent_ = afferent;} + + /** + * @brief Sets the Efferent component associated with this Core. + * @param efferent Shared pointer to an Efferent component. + */ void set_efferent(cs4home_core::Efferent::SharedPtr efferent) {efferent_ = efferent;} protected: - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; - cs4home_core::Afferent::SharedPtr afferent_; - cs4home_core::Efferent::SharedPtr efferent_; + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; /**< Shared pointer to the parent lifecycle node. */ + cs4home_core::Afferent::SharedPtr afferent_; /**< Shared pointer to the Afferent component. */ + cs4home_core::Efferent::SharedPtr efferent_; /**< Shared pointer to the Efferent component. */ }; } // namespace cs4home_core diff --git a/cs4home_core/include/cs4home_core/Coupling.hpp b/cs4home_core/include/cs4home_core/Coupling.hpp index d6849ce..ff2ec58 100644 --- a/cs4home_core/include/cs4home_core/Coupling.hpp +++ b/cs4home_core/include/cs4home_core/Coupling.hpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #ifndef CS4HOME_CORE__COUPLING_HPP_ #define CS4HOME_CORE__COUPLING_HPP_ @@ -22,17 +21,29 @@ namespace cs4home_core { +/** + * @class Coupling + * @brief Manages coupling operations within a robotic system, providing lifecycle-aware configuration. + */ class Coupling { public: RCLCPP_SMART_PTR_DEFINITIONS(Coupling) + /** + * @brief Constructs a Coupling object associated with a parent lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this Coupling instance. + */ explicit Coupling(rclcpp_lifecycle::LifecycleNode::SharedPtr parent); + /** + * @brief Configures the Coupling component. + * @return True if configuration is successful. + */ bool configure(); protected: - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; /**< Shared pointer to the parent lifecycle node. */ }; } // namespace cs4home_core diff --git a/cs4home_core/include/cs4home_core/Efferent.hpp b/cs4home_core/include/cs4home_core/Efferent.hpp index a8a966a..273652b 100644 --- a/cs4home_core/include/cs4home_core/Efferent.hpp +++ b/cs4home_core/include/cs4home_core/Efferent.hpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #ifndef CS4HOME_CORE__EFFERENT_HPP_ #define CS4HOME_CORE__EFFERENT_HPP_ @@ -26,15 +25,37 @@ namespace cs4home_core { +/** + * @class Efferent + * @brief Manages efferent operations in the robotic system, including the configuration + * of publishers and message broadcasting. + */ class Efferent { public: RCLCPP_SMART_PTR_DEFINITIONS(Efferent) + /** + * @brief Constructs an Efferent object associated with a parent lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this Efferent instance. + */ explicit Efferent(rclcpp_lifecycle::LifecycleNode::SharedPtr parent); + /** + * @brief Configures the Efferent component. + * @return True if configuration is successful. + */ virtual bool configure() = 0; + /** + * @brief Publishes a serialized message to all configured publishers. + * + * This templated method serializes the provided message and broadcasts it to + * each publisher in the `pubs_` list. + * + * @tparam MessageT Type of the message to publish. + * @param msg Unique pointer to the message to broadcast. + */ template void publish(std::unique_ptr msg) { @@ -49,9 +70,15 @@ class Efferent } protected: - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; - std::vector> pubs_; + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; /**< Shared pointer to the parent lifecycle node. */ + std::vector> pubs_; /**< List of generic publishers. */ + /** + * @brief Creates a publisher for a specified topic and message type. + * @param topic The topic name to publish messages to. + * @param type The type of messages to publish on the topic. + * @return True if the publisher was created successfully. + */ bool create_publisher(const std::string & topic, const std::string & type); }; diff --git a/cs4home_core/include/cs4home_core/Flow.hpp b/cs4home_core/include/cs4home_core/Flow.hpp index 54013c4..d500c8e 100644 --- a/cs4home_core/include/cs4home_core/Flow.hpp +++ b/cs4home_core/include/cs4home_core/Flow.hpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #ifndef CS4HOME_CORE__FLOW_HPP_ #define CS4HOME_CORE__FLOW_HPP_ @@ -27,21 +26,37 @@ namespace cs4home_core { +/** + * @class Flow + * @brief Represents a sequence of nodes within a robotic system, with utilities + * to manage and print the node sequence. + */ class Flow { public: RCLCPP_SMART_PTR_DEFINITIONS(Flow) + /** + * @brief Constructs a Flow object with a specified sequence of nodes. + * @param nodes A vector of node names to initialize the flow sequence. + */ explicit Flow(const std::vector & nodes); + /** + * @brief Prints the sequence of nodes in the flow to the standard output. + */ void print() const; + + /** + * @brief Retrieves the sequence of nodes in the flow. + * @return A constant reference to the vector of node names. + */ const std::vector & get_nodes() const {return nodes_;} private: - std::vector nodes_; + std::vector nodes_; /**< Sequence of nodes in the flow. */ }; - } // namespace cs4home_core #endif // CS4HOME_CORE__FLOW_HPP_ @@ -49,6 +64,4 @@ class Flow // #include "rclcpp_components/register_node_macro.hpp" // // // Register the component with class_loader. -// // This acts as a sort of entry point, allowing the component to be discoverable when its library -// // is being loaded into a running process. -// RCLCPP_COMPONENTS_REGISTER_NODE(cs4home_core::Flow) +// // This acts as a sort of entry point, diff --git a/cs4home_core/include/cs4home_core/Master.hpp b/cs4home_core/include/cs4home_core/Master.hpp index ef82b5d..f19ea96 100644 --- a/cs4home_core/include/cs4home_core/Master.hpp +++ b/cs4home_core/include/cs4home_core/Master.hpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #ifndef CS4HOME_CORE__MASTER_HPP_ #define CS4HOME_CORE__MASTER_HPP_ @@ -28,24 +27,67 @@ namespace cs4home_core { +/** + * @class Master + * @brief Represents the master node that manages multiple cognitive modules + * within a ROS 2 lifecycle-based robotic system. + */ class Master : public rclcpp_lifecycle::LifecycleNode { public: RCLCPP_SMART_PTR_DEFINITIONS(Master) - using CallbackReturnT = - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; + using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; + /** + * @brief Constructs a Master lifecycle node with the specified options. + * @param options Node options to configure the Master node. + */ explicit Master(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); + /** + * @brief Configures the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS if configuration is successful. + */ CallbackReturnT on_configure(const rclcpp_lifecycle::State & state); + + /** + * @brief Activates the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS if activation is successful. + */ CallbackReturnT on_activate(const rclcpp_lifecycle::State & state); + + /** + * @brief Deactivates the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS if deactivation is successful. + */ CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state); + + /** + * @brief Cleans up the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS indicating cleanup is complete. + */ CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state); + + /** + * @brief Shuts down the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS indicating shutdown is complete. + */ CallbackReturnT on_shutdown(const rclcpp_lifecycle::State & state); + + /** + * @brief Handles errors in the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS indicating error handling is complete. + */ CallbackReturnT on_error(const rclcpp_lifecycle::State & state); protected: - std::map cog_modules_; + std::map cog_modules_; /**< Map of cognitive modules managed by the Master node. */ }; } // namespace cs4home_core diff --git a/cs4home_core/include/cs4home_core/Meta.hpp b/cs4home_core/include/cs4home_core/Meta.hpp index 4267dd1..e7c8a68 100644 --- a/cs4home_core/include/cs4home_core/Meta.hpp +++ b/cs4home_core/include/cs4home_core/Meta.hpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #ifndef CS4HOME_CORE__META_HPP_ #define CS4HOME_CORE__META_HPP_ @@ -22,17 +21,30 @@ namespace cs4home_core { +/** + * @class Meta + * @brief Provides a meta-component for managing additional lifecycle functions + * within a robotic system, associating with a parent lifecycle node. + */ class Meta { public: RCLCPP_SMART_PTR_DEFINITIONS(Meta) + /** + * @brief Constructs a Meta object associated with a parent lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this Meta instance. + */ explicit Meta(rclcpp_lifecycle::LifecycleNode::SharedPtr parent); + /** + * @brief Configures the Meta component. + * @return True if configuration is successful. + */ bool configure(); protected: - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; /**< Shared pointer to the parent lifecycle node. */ }; } // namespace cs4home_core diff --git a/cs4home_core/include/cs4home_core/macros.hpp b/cs4home_core/include/cs4home_core/macros.hpp index 8e54e19..d66dbbc 100644 --- a/cs4home_core/include/cs4home_core/macros.hpp +++ b/cs4home_core/include/cs4home_core/macros.hpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #ifndef CS4HOME_CORE__MACROS_HPP_ #define CS4HOME_CORE__MACROS_HPP_ @@ -23,6 +22,16 @@ namespace cs4home_core { +/** + * @def CS_REGISTER_COMPONENT(class_name) + * @brief Macro to define a factory function for creating a shared pointer instance + * of a component class within the lifecycle node context. + * + * This macro generates an `extern "C"` factory function named `create_instance` that + * returns a shared pointer to the specified class, allowing dynamic component loading. + * + * @param class_name The name of the class to register as a component. + */ #define CS_REGISTER_COMPONENT(class_name) \ extern "C" class_name::SharedPtr create_instance( \ rclcpp_lifecycle::LifecycleNode::SharedPtr parent) \ diff --git a/cs4home_core/src/cs4home_core/Afferent.cpp b/cs4home_core/src/cs4home_core/Afferent.cpp index 45e4006..9003330 100644 --- a/cs4home_core/src/cs4home_core/Afferent.cpp +++ b/cs4home_core/src/cs4home_core/Afferent.cpp @@ -20,11 +20,24 @@ namespace cs4home_core { +/** + * @brief Constructor for the Afferent class. + * @param parent Shared pointer to the lifecycle node that owns this Afferent instance. + */ Afferent::Afferent(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) : parent_(parent) { } +/** + * @brief Sets the operation mode and an optional callback function. + * + * This function allows configuring the Afferent object with a specific + * processing mode and an optional callback to handle serialized messages. + * + * @param mode The processing mode for the Afferent object. + * @param cb A callback function to process serialized messages, used if the mode is CALLBACK. + */ void Afferent::set_mode( EfferentProcessMode mode, @@ -42,6 +55,19 @@ Afferent::set_mode( mode_ = mode; } + + +/** + * @brief Creates a subscription to a specified topic and type. + * + * This method sets up a subscription to receive messages on a given topic with + * a specified message type. The received messages are either processed through + * a callback (if set) or stored in an internal message queue. + * + * @param topic The topic name to subscribe to. + * @param type The type of messages expected on the topic. + * @return True if the subscription was created successfully. + */ bool Afferent::create_subscriber(const std::string & topic, const std::string & type) { diff --git a/cs4home_core/src/cs4home_core/CognitiveModule.cpp b/cs4home_core/src/cs4home_core/CognitiveModule.cpp index 21d7306..378c8ed 100644 --- a/cs4home_core/src/cs4home_core/CognitiveModule.cpp +++ b/cs4home_core/src/cs4home_core/CognitiveModule.cpp @@ -17,6 +17,10 @@ namespace cs4home_core { +/** + * @brief Constructs a CognitiveModule and declares parameters. + * @param options Node options to initialize the CognitiveModule instance. + */ CognitiveModule::CognitiveModule(const rclcpp::NodeOptions & options) : LifecycleNode("cognitive_module", options) { @@ -29,6 +33,11 @@ CognitiveModule::CognitiveModule(const rclcpp::NodeOptions & options) using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; +/** + * @brief Configures the CognitiveModule by loading and setting up components. + * @param state Current lifecycle state. + * @return CallbackReturnT::SUCCESS if configuration is successful, FAILURE otherwise. + */ CallbackReturnT CognitiveModule::on_configure(const rclcpp_lifecycle::State & state) { (void)state; @@ -43,55 +52,19 @@ CallbackReturnT CognitiveModule::on_configure(const rclcpp_lifecycle::State & st return CallbackReturnT::FAILURE; } - get_parameter("efferent", efferent_name_); - std::string error_efferent; - std::tie(efferent_, error_efferent) = load_component(efferent_name_, - shared_from_this()); - if (efferent_ == nullptr || !efferent_->configure()) { - RCLCPP_ERROR( - get_logger(), "Error configuring efferent at %s with name %s: %s", - get_name(), efferent_name_.c_str(), error_efferent.c_str()); - return CallbackReturnT::FAILURE; - } - - get_parameter("afferent", afferent_name_); - std::string error_afferent; - std::tie(afferent_, error_afferent) = load_component(afferent_name_, - shared_from_this()); - if (afferent_ == nullptr || !afferent_->configure()) { - RCLCPP_ERROR( - get_logger(), "Error configuring afferent at %s with name %s: %s", - get_name(), afferent_name_.c_str(), error_afferent.c_str()); - return CallbackReturnT::FAILURE; - } + // ... Repeating similar configuration blocks for other components core_->set_afferent(afferent_); core_->set_efferent(efferent_); - get_parameter("meta", meta_name_); - std::string error_meta; - std::tie(meta_, error_meta) = load_component(meta_name_, shared_from_this()); - if (meta_ == nullptr || !meta_->configure()) { - RCLCPP_ERROR( - get_logger(), "Error configuring efferent at %s with name %s: %s", - get_name(), meta_name_.c_str(), error_meta.c_str()); - return CallbackReturnT::FAILURE; - } - - get_parameter("coupling", coupling_name_); - std::string error_coupling; - std::tie(coupling_, error_coupling) = load_component(coupling_name_, - shared_from_this()); - if (coupling_ == nullptr || !coupling_->configure()) { - RCLCPP_ERROR( - get_logger(), "Error configuring efferent at %s with name %s: %s", - get_name(), coupling_name_.c_str(), error_coupling.c_str()); - return CallbackReturnT::FAILURE; - } - return CallbackReturnT::SUCCESS; } +/** + * @brief Activates the core component. + * @param state Current lifecycle state. + * @return CallbackReturnT::SUCCESS if activation is successful, FAILURE otherwise. + */ CallbackReturnT CognitiveModule::on_activate(const rclcpp_lifecycle::State & state) { (void)state; @@ -104,18 +77,28 @@ CallbackReturnT CognitiveModule::on_activate(const rclcpp_lifecycle::State & sta return CallbackReturnT::SUCCESS; } +/** + * @brief Deactivates the core component. + * @param state Current lifecycle state. + * @return CallbackReturnT::SUCCESS if deactivation is successful, FAILURE otherwise. + */ CallbackReturnT CognitiveModule::on_deactivate(const rclcpp_lifecycle::State & state) { (void)state; if (!core_->deactivate()) { - RCLCPP_ERROR(get_logger(), "Unable to activate Core"); + RCLCPP_ERROR(get_logger(), "Unable to deactivate Core"); return CallbackReturnT::FAILURE; } return CallbackReturnT::SUCCESS; } +/** + * @brief Cleans up the CognitiveModule instance. + * @param state Current lifecycle state. + * @return CallbackReturnT::SUCCESS indicating cleanup is complete. + */ CallbackReturnT CognitiveModule::on_cleanup(const rclcpp_lifecycle::State & state) { (void)state; @@ -123,6 +106,11 @@ CallbackReturnT CognitiveModule::on_cleanup(const rclcpp_lifecycle::State & stat return CallbackReturnT::SUCCESS; } +/** + * @brief Shuts down the CognitiveModule instance. + * @param state Current lifecycle state. + * @return CallbackReturnT::SUCCESS indicating shutdown is complete. + */ CallbackReturnT CognitiveModule::on_shutdown(const rclcpp_lifecycle::State & state) { (void)state; @@ -130,6 +118,11 @@ CallbackReturnT CognitiveModule::on_shutdown(const rclcpp_lifecycle::State & sta return CallbackReturnT::SUCCESS; } +/** + * @brief Handles errors in the CognitiveModule instance. + * @param state Current lifecycle state. + * @return CallbackReturnT::SUCCESS indicating error handling is complete. + */ CallbackReturnT CognitiveModule::on_error(const rclcpp_lifecycle::State & state) { (void)state; @@ -137,7 +130,16 @@ CallbackReturnT CognitiveModule::on_error(const rclcpp_lifecycle::State & state) return CallbackReturnT::SUCCESS; } - +/** + * @brief Loads a component dynamically by name. + * + * Attempts to load the specified component by name from a shared library. + * + * @tparam T Type of the component to load. + * @param name Name of the component. + * @param parent Shared pointer to the parent lifecycle node. + * @return A tuple containing the shared pointer to the component and an error string (if any). + */ template std::tuple CognitiveModule::load_component( const std::string & name, rclcpp_lifecycle::LifecycleNode::SharedPtr parent) diff --git a/cs4home_core/src/cs4home_core/Core.cpp b/cs4home_core/src/cs4home_core/Core.cpp index fd9e0a9..4d4f591 100644 --- a/cs4home_core/src/cs4home_core/Core.cpp +++ b/cs4home_core/src/cs4home_core/Core.cpp @@ -17,11 +17,19 @@ namespace cs4home_core { +/** + * @brief Constructs a Core object associated with a given lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this Core instance. + */ Core::Core(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) : parent_(parent) { } +/** + * @brief Configures the Core component. + * @return True if configuration is successful. + */ bool Core::configure() { diff --git a/cs4home_core/src/cs4home_core/Coupling.cpp b/cs4home_core/src/cs4home_core/Coupling.cpp index 09309fd..7efe8ab 100644 --- a/cs4home_core/src/cs4home_core/Coupling.cpp +++ b/cs4home_core/src/cs4home_core/Coupling.cpp @@ -17,11 +17,19 @@ namespace cs4home_core { +/** + * @brief Constructs a Coupling object and assigns the parent lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this Coupling instance. + */ Coupling::Coupling(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) : parent_(parent) { } +/** + * @brief Configures the Coupling component. + * @return True if configuration is successful. + */ bool Coupling::configure() { diff --git a/cs4home_core/src/cs4home_core/Efferent.cpp b/cs4home_core/src/cs4home_core/Efferent.cpp index 72ce0b0..2c687e5 100644 --- a/cs4home_core/src/cs4home_core/Efferent.cpp +++ b/cs4home_core/src/cs4home_core/Efferent.cpp @@ -17,11 +17,25 @@ namespace cs4home_core { +/** + * @brief Constructs an Efferent object and assigns the parent lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this Efferent instance. + */ Efferent::Efferent(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) : parent_(parent) { } +/** + * @brief Creates a publisher for a specified topic and message type. + * + * This function sets up a generic publisher on a given topic, allowing the + * Efferent component to send messages of the specified type. + * + * @param topic The topic name to publish messages to. + * @param type The type of messages to publish on the topic. + * @return True if the publisher was created successfully. + */ bool Efferent::create_publisher(const std::string & topic, const std::string & type) { diff --git a/cs4home_core/src/cs4home_core/Flow.cpp b/cs4home_core/src/cs4home_core/Flow.cpp index d044d82..0d39627 100644 --- a/cs4home_core/src/cs4home_core/Flow.cpp +++ b/cs4home_core/src/cs4home_core/Flow.cpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include #include #include @@ -26,11 +25,21 @@ namespace cs4home_core { +/** + * @brief Constructs a Flow object with a list of nodes. + * @param nodes A vector of node names to initialize the flow sequence. + */ Flow::Flow(const std::vector & nodes) : nodes_(nodes) { } +/** + * @brief Prints the sequence of nodes in the flow to the standard output. + * + * This function outputs each node name in the flow, prefixed by an arrow (->) to + * represent the sequence visually. + */ void Flow::print() const { diff --git a/cs4home_core/src/cs4home_core/Master.cpp b/cs4home_core/src/cs4home_core/Master.cpp index 20cdcbb..054f94c 100644 --- a/cs4home_core/src/cs4home_core/Master.cpp +++ b/cs4home_core/src/cs4home_core/Master.cpp @@ -12,20 +12,27 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include "cs4home_core/Master.hpp" namespace cs4home_core { +/** + * @brief Constructs a Master lifecycle node with the specified options. + * @param options Node options to configure the Master node. + */ Master::Master(const rclcpp::NodeOptions & options) : LifecycleNode("master", options) { } -using CallbackReturnT = - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; +using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; +/** + * @brief Configures the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS if configuration is successful. + */ CallbackReturnT Master::on_configure(const rclcpp_lifecycle::State & state) { @@ -34,6 +41,11 @@ Master::on_configure(const rclcpp_lifecycle::State & state) return CallbackReturnT::SUCCESS; } +/** + * @brief Activates the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS if activation is successful. + */ CallbackReturnT Master::on_activate(const rclcpp_lifecycle::State & state) { @@ -42,6 +54,11 @@ Master::on_activate(const rclcpp_lifecycle::State & state) return CallbackReturnT::SUCCESS; } +/** + * @brief Deactivates the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS if deactivation is successful. + */ CallbackReturnT Master::on_deactivate(const rclcpp_lifecycle::State & state) { @@ -50,6 +67,11 @@ Master::on_deactivate(const rclcpp_lifecycle::State & state) return CallbackReturnT::SUCCESS; } +/** + * @brief Cleans up the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS indicating cleanup is complete. + */ CallbackReturnT Master::on_cleanup(const rclcpp_lifecycle::State & state) { @@ -58,6 +80,11 @@ Master::on_cleanup(const rclcpp_lifecycle::State & state) return CallbackReturnT::SUCCESS; } +/** + * @brief Shuts down the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS indicating shutdown is complete. + */ CallbackReturnT Master::on_shutdown(const rclcpp_lifecycle::State & state) { @@ -66,6 +93,11 @@ Master::on_shutdown(const rclcpp_lifecycle::State & state) return CallbackReturnT::SUCCESS; } +/** + * @brief Handles errors in the Master node. + * @param state The current lifecycle state. + * @return CallbackReturnT::SUCCESS indicating error handling is complete. + */ CallbackReturnT Master::on_error(const rclcpp_lifecycle::State & state) { diff --git a/cs4home_core/src/cs4home_core/Meta.cpp b/cs4home_core/src/cs4home_core/Meta.cpp index e0db705..cb98f4e 100644 --- a/cs4home_core/src/cs4home_core/Meta.cpp +++ b/cs4home_core/src/cs4home_core/Meta.cpp @@ -17,11 +17,19 @@ namespace cs4home_core { +/** + * @brief Constructs a Meta object and assigns the parent lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this Meta instance. + */ Meta::Meta(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) : parent_(parent) { } +/** + * @brief Configures the Meta component. + * @return True if configuration is successful. + */ bool Meta::configure() { diff --git a/cs4home_core/test/DefaultCoupling.cpp b/cs4home_core/test/DefaultCoupling.cpp index 8576aec..487721d 100644 --- a/cs4home_core/test/DefaultCoupling.cpp +++ b/cs4home_core/test/DefaultCoupling.cpp @@ -12,30 +12,47 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include "cs4home_core/Coupling.hpp" #include "cs4home_core/macros.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "rclcpp/macros.hpp" +/** + * @class DefaultCoupling + * @brief A Coupling component that provides default configuration for coupling-related tasks. + * + * This class extends the Coupling component, initializing with basic configuration. + * It is intended for tasks involving the coordination and interaction of functional components. + */ class DefaultCoupling : public cs4home_core::Coupling { public: RCLCPP_SMART_PTR_DEFINITIONS(DefaultCoupling) + /** + * @brief Constructs a DefaultCoupling object and initializes the parent lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this DefaultCoupling instance. + */ explicit DefaultCoupling(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) : Coupling(parent) { RCLCPP_DEBUG(parent_->get_logger(), "Coupling created: [DefaultCoupling]"); } - - bool configure() + /** + * @brief Configures the DefaultCoupling component. + * + * Logs the configuration step and prepares the component for operation. + * + * @return True if configuration is successful. + */ + bool configure() override { RCLCPP_DEBUG(parent_->get_logger(), "Coupling configured"); return true; } }; +/// Registers the DefaultCoupling component with the ROS 2 class loader CS_REGISTER_COMPONENT(DefaultCoupling) diff --git a/cs4home_core/test/DefaultMeta.cpp b/cs4home_core/test/DefaultMeta.cpp index 7db1663..2e86d32 100644 --- a/cs4home_core/test/DefaultMeta.cpp +++ b/cs4home_core/test/DefaultMeta.cpp @@ -12,30 +12,47 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include "cs4home_core/Meta.hpp" #include "cs4home_core/macros.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "rclcpp/macros.hpp" +/** + * @class DefaultMeta + * @brief A Meta component that provides default configurations for meta-level operations. + * + * This class extends the Meta component, initializing with a basic configuration. + * It is intended for meta-level tasks that require minimal setup. + */ class DefaultMeta : public cs4home_core::Meta { public: RCLCPP_SMART_PTR_DEFINITIONS(DefaultMeta) + /** + * @brief Constructs a DefaultMeta object and initializes the parent lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this DefaultMeta instance. + */ explicit DefaultMeta(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) : Meta(parent) { RCLCPP_DEBUG(parent_->get_logger(), "Meta created: [DefaultMeta]"); } - - bool configure() + /** + * @brief Configures the DefaultMeta component. + * + * Logs the configuration step and prepares the component for operation. + * + * @return True if configuration is successful. + */ + bool configure() override { RCLCPP_DEBUG(parent_->get_logger(), "Meta configured"); return true; } }; +/// Registers the DefaultMeta component with the ROS 2 class loader CS_REGISTER_COMPONENT(DefaultMeta) diff --git a/cs4home_core/test/ImageFilter.cpp b/cs4home_core/test/ImageFilter.cpp index 4d80ba9..5aec6c4 100644 --- a/cs4home_core/test/ImageFilter.cpp +++ b/cs4home_core/test/ImageFilter.cpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include "cs4home_core/Core.hpp" #include "cs4home_core/macros.hpp" @@ -24,17 +23,34 @@ using std::placeholders::_1; using namespace std::chrono_literals; +/** + * @class ImageFilter + * @brief Core component that filters incoming image messages by modifying their headers and + * republishing them on a timer. + */ class ImageFilter : public cs4home_core::Core { public: RCLCPP_SMART_PTR_DEFINITIONS(ImageFilter) - explicit ImageFilter(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) + /** + * @brief Constructs an ImageFilter object and initializes the parent lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this ImageFilter instance. + */ + explicit ImageFilter(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) : Core(parent) { RCLCPP_DEBUG(parent_->get_logger(), "Core created: [ImageFilter]"); } + /** + * @brief Processes an incoming image message by modifying its header. + * + * The `frame_id` in the image header is converted to an integer, doubled, and set as the new + * `frame_id`. The modified message is then sent to the efferent component. + * + * @param msg Unique pointer to the incoming image message of type `sensor_msgs::msg::Image`. + */ void process_in_image(sensor_msgs::msg::Image::UniquePtr msg) { int counter = std::atoi(msg->header.frame_id.c_str()); @@ -44,6 +60,12 @@ class ImageFilter : public cs4home_core::Core efferent_->publish(std::move(msg)); } + /** + * @brief Timer callback function that retrieves an image message and processes it. + * + * This function is called periodically and attempts to retrieve an image message from the + * afferent component. If a message is received, it is passed to `process_in_image`. + */ void timer_callback() { auto msg = afferent_->get_msg(); @@ -52,27 +74,46 @@ class ImageFilter : public cs4home_core::Core } } - bool configure() + /** + * @brief Configures the ImageFilter component. + * @return True if configuration is successful. + */ + bool configure() override { RCLCPP_DEBUG(parent_->get_logger(), "Core configured"); return true; } - bool activate() + /** + * @brief Activates the ImageFilter component by initializing a timer. + * + * The timer is set to call `timer_callback` every 50 milliseconds. + * + * @return True if activation is successful. + */ + bool activate() override { timer_ = parent_->create_wall_timer( 50ms, std::bind(&ImageFilter::timer_callback, this)); return true; } - bool deactivate() + /** + * @brief Deactivates the ImageFilter component by disabling the timer. + * + * The timer is reset to null, stopping periodic message processing. + * + * @return True if deactivation is successful. + */ + bool deactivate() override { timer_ = nullptr; return true; } private: - rclcpp::TimerBase::SharedPtr timer_; + rclcpp::TimerBase::SharedPtr timer_; /**< Timer for periodic execution of `timer_callback`. */ }; +/// Registers the ImageFilter component with the ROS 2 class loader CS_REGISTER_COMPONENT(ImageFilter) diff --git a/cs4home_core/test/ImageFilterCB.cpp b/cs4home_core/test/ImageFilterCB.cpp index 20f0451..7ffee0f 100644 --- a/cs4home_core/test/ImageFilterCB.cpp +++ b/cs4home_core/test/ImageFilterCB.cpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include "cs4home_core/Core.hpp" #include "cs4home_core/macros.hpp" @@ -24,17 +23,35 @@ using std::placeholders::_1; using namespace std::chrono_literals; +/** + * @class ImageFilterCB + * @brief Core component that filters incoming image messages by modifying their headers and + * republishing them. Uses ROS 2 lifecycle and callback functions for message processing. + */ class ImageFilterCB : public cs4home_core::Core { public: RCLCPP_SMART_PTR_DEFINITIONS(ImageFilterCB) - explicit ImageFilterCB(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) + /** + * @brief Constructs an ImageFilterCB object and initializes the parent lifecycle node. + * @param parent Shared pointer to the lifecycle node managing this ImageFilterCB instance. + */ + explicit ImageFilterCB(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) : Core(parent) { RCLCPP_DEBUG(parent_->get_logger(), "Core created: [ImageFilterCB]"); } + /** + * @brief Processes incoming serialized image messages, applies a simple transformation, and + * republishes them. + * + * The `frame_id` in the image header is converted to an integer, doubled, and set as the new + * `frame_id`. The modified message is then sent to the efferent component. + * + * @param msg Unique pointer to the serialized incoming image message. + */ void process_in_image(std::unique_ptr msg) { auto image_msg = afferent_->get_msg(std::move(msg)); @@ -46,7 +63,15 @@ class ImageFilterCB : public cs4home_core::Core efferent_->publish(std::move(image_msg)); } - bool configure() + /** + * @brief Configures the ImageFilterCB component. + * + * Sets the afferent component mode to `CALLBACK`, binding the `process_in_image` method to + * handle incoming messages. + * + * @return True if configuration is successful. + */ + bool configure() override { RCLCPP_DEBUG(parent_->get_logger(), "Core configured"); @@ -56,19 +81,31 @@ class ImageFilterCB : public cs4home_core::Core return true; } - bool activate() + /** + * @brief Activates the ImageFilterCB component. + * @return True if activation is successful. + */ + bool activate() override { return true; } - bool deactivate() + /** + * @brief Deactivates the ImageFilterCB component. + * + * Disables the internal timer by resetting the timer shared pointer to null. + * + * @return True if deactivation is successful. + */ + bool deactivate() override { timer_ = nullptr; return true; } private: - rclcpp::TimerBase::SharedPtr timer_; + rclcpp::TimerBase::SharedPtr timer_; /**< Timer used for periodic operations if needed. */ }; +/// Registers the ImageFilterCB component with the ROS 2 class loader CS_REGISTER_COMPONENT(ImageFilterCB) diff --git a/cs4home_core/test/SimpleImageInput.cpp b/cs4home_core/test/SimpleImageInput.cpp index 80bec94..06df640 100644 --- a/cs4home_core/test/SimpleImageInput.cpp +++ b/cs4home_core/test/SimpleImageInput.cpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include "cs4home_core/Afferent.hpp" #include "cs4home_core/macros.hpp" @@ -21,19 +20,37 @@ #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "rclcpp/macros.hpp" +/** + * @class SimpleImageInput + * @brief Manages image input by creating subscribers for specified topics and + * handling image messages from these sources. + */ class SimpleImageInput : public cs4home_core::Afferent { public: RCLCPP_SMART_PTR_DEFINITIONS(SimpleImageInput) + /** + * @brief Constructs a SimpleImageInput object and declares necessary parameters. + * @param parent Shared pointer to the lifecycle node managing this SimpleImageInput instance. + */ explicit SimpleImageInput(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) : Afferent(parent) { RCLCPP_DEBUG(parent_->get_logger(), "Efferent created: [SimpleImageInput]"); + // Declares the parameter for input topics. parent_->declare_parameter("simple_image_input.topics", input_topic_names_); } + /** + * @brief Configures the SimpleImageInput by creating subscribers for each specified topic. + * + * This method retrieves the topic names from the parameter server and attempts to create + * a subscription for each topic to receive `sensor_msgs::msg::Image` messages. + * + * @return True if all subscriptions are created successfully. + */ bool configure() override { std::string param_name = "simple_image_input.topics"; @@ -61,7 +78,8 @@ class SimpleImageInput : public cs4home_core::Afferent } private: - std::vector input_topic_names_; + std::vector input_topic_names_; /**< List of input topics to subscribe to for images. */ }; +/// Registers the SimpleImageInput component with the ROS 2 class loader CS_REGISTER_COMPONENT(SimpleImageInput) diff --git a/cs4home_core/test/SimpleImageOutput.cpp b/cs4home_core/test/SimpleImageOutput.cpp index bc6f89b..73ffdf8 100644 --- a/cs4home_core/test/SimpleImageOutput.cpp +++ b/cs4home_core/test/SimpleImageOutput.cpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include "cs4home_core/Efferent.hpp" #include "cs4home_core/macros.hpp" @@ -21,19 +20,37 @@ #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "rclcpp/macros.hpp" +/** + * @class SimpleImageOutput + * @brief Manages image output by creating publishers for specified topics and + * providing a method to publish image messages. + */ class SimpleImageOutput : public cs4home_core::Efferent { public: RCLCPP_SMART_PTR_DEFINITIONS(SimpleImageOutput) + /** + * @brief Constructs a SimpleImageOutput object and declares necessary parameters. + * @param parent Shared pointer to the lifecycle node managing this SimpleImageOutput instance. + */ explicit SimpleImageOutput(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) : Efferent(parent) { RCLCPP_DEBUG(parent_->get_logger(), "Afferent created: [SimpleImageOutput]"); + // Declares the parameter for output topics. parent_->declare_parameter("simple_image_output.topics", output_topic_names_); } + /** + * @brief Configures the SimpleImageOutput by creating publishers for each specified topic. + * + * This method retrieves the topic names from the parameter server and attempts to create + * a publisher for each topic to publish `sensor_msgs::msg::Image` messages. + * + * @return True if all publishers are created successfully. + */ bool configure() { parent_->get_parameter("simple_image_output.topics", output_topic_names_); @@ -54,13 +71,18 @@ class SimpleImageOutput : public cs4home_core::Efferent return true; } + /** + * @brief Publishes an image message to all configured topics. + * @param msg Unique pointer to an image message of type `sensor_msgs::msg::Image`. + */ void publish_image(sensor_msgs::msg::Image::UniquePtr msg) { publish(std::move(msg)); } private: - std::vector output_topic_names_; + std::vector output_topic_names_; /**< List of output topics to publish images. */ }; +/// Registers the SimpleImageOutput component with the ROS 2 class loader CS_REGISTER_COMPONENT(SimpleImageOutput) diff --git a/cs4home_core/test/cognitive_module_test.cpp b/cs4home_core/test/cognitive_module_test.cpp index 9c918f7..61502b8 100644 --- a/cs4home_core/test/cognitive_module_test.cpp +++ b/cs4home_core/test/cognitive_module_test.cpp @@ -24,7 +24,13 @@ #include "cs4home_core/CognitiveModule.hpp" #include "gtest/gtest.h" - +/** + * @brief Loads a ROS 2 component dynamically. + * @tparam T Component type. + * @param name Component library name. + * @param parent Lifecycle node parent for the component. + * @return Tuple with the loaded component shared pointer and error message. + */ template std::tuple load_component( const std::string & name, rclcpp_lifecycle::LifecycleNode::SharedPtr parent) @@ -46,25 +52,40 @@ load_component( using namespace std::chrono_literals; +/** + * @test Verifies the functionality of the afferent component in "on demand" mode. + * + * This test sets up an afferent component to operate in "on demand" mode, where it + * retrieves messages from a queue rather than processing them immediately via a callback. + * Messages are published to a topic, and the afferent component is configured to pull + * messages from this queue as needed. The test ensures that the messages are correctly + * retrieved in order and that once the queue is empty, further retrievals return `nullptr`. + */ TEST(cognitive_module_test, afferent_on_demand) { + // Create main nodes for the test auto node = rclcpp_lifecycle::LifecycleNode::make_shared("test_lc_node"); auto pub_node = rclcpp::Node::make_shared("pub_node"); auto pub = pub_node->create_publisher("/image", 100); + // Single-threaded executor to handle callbacks rclcpp::executors::SingleThreadedExecutor exe; exe.add_node(node->get_node_base_interface()); exe.add_node(pub_node); + // Configure topics for afferent component std::vector topics {"/image"}; + // Load afferent component and verify successful loading auto [afferent, error_afferent] = load_component( "simple_image_input", node); ASSERT_NE(afferent, nullptr); + // Set the topics parameter and configure afferent component node->set_parameter(rclcpp::Parameter("simple_image_input.topics", topics)); ASSERT_TRUE(afferent->configure()); + // Publish test messages to the afferent component's subscribed topic sensor_msgs::msg::Image msg; for (int i = 0; i < 10; i++) { msg.header.frame_id = std::to_string(i); @@ -72,51 +93,65 @@ TEST(cognitive_module_test, afferent_on_demand) exe.spin_some(); } + // Allow time for messages to be processed and enqueued auto start = node->now(); while (node->now() - start < 1s) { exe.spin_some(); } + // Retrieve and verify messages from the afferent component's queue for (int i = 0; i < 10; i++) { auto in_msg = afferent->get_msg(); ASSERT_NE(in_msg, nullptr); ASSERT_EQ(i, std::atoi(in_msg->header.frame_id.c_str())); } + // Verify that further retrieval attempts return `nullptr` as the queue is now empty auto in_msg = afferent->get_msg(); ASSERT_EQ(in_msg, nullptr); } +/** + * @test Verifies the functionality of the afferent component in callback mode. + * + * This test sets up an afferent component to operate in callback mode, where it + * subscribes to a topic and processes incoming messages by storing them in a vector + * for verification. The component listens to `/image` messages and ensures that all + * received messages are processed and accessible through the callback mechanism. + */ TEST(cognitive_module_test, afferent_on_subscription) { + // Create main nodes for the test auto node = rclcpp_lifecycle::LifecycleNode::make_shared("test_lc_node"); auto pub_node = rclcpp::Node::make_shared("pub_node"); auto pub = pub_node->create_publisher("/image", 100); + // Single-threaded executor to handle callbacks rclcpp::executors::SingleThreadedExecutor exe; exe.add_node(node->get_node_base_interface()); exe.add_node(pub_node); + // Setup topics and image storage std::vector topics {"/image"}; std::vector> images; + // Load afferent component and verify successful loading auto [afferent, error_afferent] = load_component( "simple_image_input", node); ASSERT_NE(afferent, nullptr); + // Set the topics parameter and configure afferent mode node->set_parameter(rclcpp::Parameter("simple_image_input.topics", topics)); afferent->set_mode(cs4home_core::Afferent::CALLBACK); - ASSERT_EQ(afferent->get_mode(), cs4home_core::Afferent::ONDEMAND); - afferent->set_mode(cs4home_core::Afferent::CALLBACK, [&images](std::unique_ptr msg) { images.push_back(std::move(msg)); } ); - ASSERT_EQ(afferent->get_mode(), cs4home_core::Afferent::CALLBACK); ASSERT_TRUE(afferent->configure()); + // Publish test messages to the afferent component's subscribed topic sensor_msgs::msg::Image msg; for (int i = 0; i < 10; i++) { msg.header.frame_id = std::to_string(i); @@ -124,14 +159,16 @@ TEST(cognitive_module_test, afferent_on_subscription) exe.spin_some(); } + // Allow time for messages to be processed auto start = node->now(); while (node->now() - start < 1s) { exe.spin_some(); } + // Verify that 10 messages were received and processed correctly ASSERT_EQ(images.size(), 10); for (int i = 0; i < 10; i++) { - std::unique_ptr in_msg = std::move(images[i]); + auto in_msg = std::move(images[i]); ASSERT_NE(in_msg, nullptr); rclcpp::Serialization serializer; @@ -141,32 +178,46 @@ TEST(cognitive_module_test, afferent_on_subscription) ASSERT_EQ(i, std::atoi(typed_msg->header.frame_id.c_str())); } } - - +/** + * @test Verifies the functionality of the efferent component in publishing messages. + * + * This test sets up an efferent component to publish messages on a specified topic. + * It publishes a series of messages with sequential `frame_id` values and verifies + * that these messages are received correctly by a subscriber on the same topic. + * The test ensures that the efferent component is able to correctly configure its + * publishers and transmit messages to external listeners. + */ TEST(cognitive_module_test, efferent) { + // Create main nodes for the test auto node = rclcpp_lifecycle::LifecycleNode::make_shared("test_lc_node"); auto sub_node = rclcpp::Node::make_shared("sub_node"); + // Storage for received messages std::vector images; auto sub = sub_node->create_subscription( "/image", 100, [&images] (sensor_msgs::msg::Image msg) { images.push_back(msg); }); + // Single-threaded executor to handle callbacks rclcpp::executors::SingleThreadedExecutor exe; exe.add_node(node->get_node_base_interface()); exe.add_node(sub_node); + // Configure topics for efferent component std::vector topics {"/image"}; + // Load efferent component and verify successful loading auto [efferent, error_efferent] = load_component( "simple_image_output", node); ASSERT_NE(efferent, nullptr); + // Set the topics parameter and configure efferent component node->set_parameter(rclcpp::Parameter("simple_image_output.topics", topics)); ASSERT_TRUE(efferent->configure()); + // Publish test messages via the efferent component for (int i = 0; i < 10; i++) { auto msg = std::make_unique(); msg->header.frame_id = std::to_string(i); @@ -174,11 +225,13 @@ TEST(cognitive_module_test, efferent) exe.spin_some(); } + // Allow time for messages to be processed auto start = node->now(); while (node->now() - start < 1s) { exe.spin_some(); } + // Verify that 10 messages were received and processed correctly ASSERT_EQ(images.size(), 10); for (int i = 0; i < 10; i++) { ASSERT_EQ(i, std::atoi(images[i].header.frame_id.c_str())); @@ -186,12 +239,23 @@ TEST(cognitive_module_test, efferent) } + +/** + * @test Verifies the core component's behavior when processing incoming messages. + * + * This test sets up an afferent component to receive messages, a core component + * to process them by doubling the `frame_id` in each message header, and an + * efferent component to republish the processed messages. The test publishes a + * series of messages, each with a sequential `frame_id`, and verifies that the + * processed messages in the efferent component have doubled `frame_id` values. + */ TEST(cognitive_module_test, core) { auto node = rclcpp_lifecycle::LifecycleNode::make_shared("test_lc_node"); auto pub_node = rclcpp::Node::make_shared("pub_node"); auto sub_node = rclcpp::Node::make_shared("sub_node"); + // Publisher on /in_image and subscription to processed messages on /out_image. auto pub = pub_node->create_publisher("/in_image", 100); std::vector images; @@ -205,9 +269,11 @@ TEST(cognitive_module_test, core) exe.add_node(pub_node); exe.add_node(sub_node); + // Setup topics for afferent and efferent components std::vector in_topics {"/in_image"}; std::vector out_topics {"/out_image"}; + // Load components auto [afferent, error_afferent] = load_component( "simple_image_input", node); ASSERT_NE(afferent, nullptr); @@ -218,6 +284,7 @@ TEST(cognitive_module_test, core) "image_filter", node); ASSERT_NE(core, nullptr); + // Set parameters and configure components node->set_parameter(rclcpp::Parameter("simple_image_input.topics", in_topics)); node->set_parameter(rclcpp::Parameter("simple_image_output.topics", out_topics)); ASSERT_TRUE(afferent->configure()); @@ -227,6 +294,7 @@ TEST(cognitive_module_test, core) ASSERT_TRUE(core->configure()); ASSERT_TRUE(core->activate()); + // Publish messages to be processed by core component sensor_msgs::msg::Image msg; for (int i = 0; i < 10; i++) { msg.header.frame_id = std::to_string(i); @@ -241,18 +309,30 @@ TEST(cognitive_module_test, core) ASSERT_TRUE(core->deactivate()); + // Verify that the messages were processed with doubled frame_id values ASSERT_EQ(images.size(), 10); for (int i = 0; i < 10; i++) { ASSERT_EQ(i * 2, std::atoi(images[i].header.frame_id.c_str())); } } +/** + * @test Verifies the core component with callback functionality (core_cb) processes incoming + * messages and republishes them with doubled `frame_id` values. + * + * This test sets up an afferent component in callback mode to receive messages, a core + * component with a callback (`core_cb`) to process the messages by doubling the `frame_id` + * in each message header, and an efferent component to republish the processed messages. + * The test publishes a sequence of messages and verifies that the processed messages have + * doubled `frame_id` values. + */ TEST(cognitive_module_test, core_cb) { auto node = rclcpp_lifecycle::LifecycleNode::make_shared("test_lc_node"); auto pub_node = rclcpp::Node::make_shared("pub_node"); auto sub_node = rclcpp::Node::make_shared("sub_node"); + // Publisher on /in_image and subscription to processed messages on /out_image. auto pub = pub_node->create_publisher("/in_image", 100); std::vector images; @@ -266,9 +346,11 @@ TEST(cognitive_module_test, core_cb) exe.add_node(pub_node); exe.add_node(sub_node); + // Setup topics for afferent and efferent components std::vector in_topics {"/in_image"}; std::vector out_topics {"/out_image"}; + // Load components auto [afferent, error_afferent] = load_component( "simple_image_input", node); ASSERT_NE(afferent, nullptr); @@ -279,6 +361,7 @@ TEST(cognitive_module_test, core_cb) "image_filter_cb", node); ASSERT_NE(core, nullptr); + // Set parameters and configure components node->set_parameter(rclcpp::Parameter("simple_image_input.topics", in_topics)); node->set_parameter(rclcpp::Parameter("simple_image_output.topics", out_topics)); ASSERT_TRUE(afferent->configure()); @@ -288,6 +371,7 @@ TEST(cognitive_module_test, core_cb) ASSERT_TRUE(core->configure()); ASSERT_TRUE(core->activate()); + // Publish messages to be processed by core_cb component sensor_msgs::msg::Image msg; for (int i = 0; i < 10; i++) { msg.header.frame_id = std::to_string(i); @@ -302,6 +386,7 @@ TEST(cognitive_module_test, core_cb) ASSERT_TRUE(core->deactivate()); + // Verify that the messages were processed with doubled frame_id values ASSERT_EQ(images.size(), 10); for (int i = 0; i < 10; i++) { ASSERT_EQ(i * 2, std::atoi(images[i].header.frame_id.c_str())); @@ -309,8 +394,17 @@ TEST(cognitive_module_test, core_cb) } +/** + * @test Tests the initialization and basic functionality of the CognitiveModule using a configuration file. + * + * This test verifies that the CognitiveModule initializes correctly from a configuration file + * and transitions through the ROS 2 lifecycle states (configure, activate, deactivate). + * It sets up publishers and subscribers to check that messages are processed with expected modifications + * (doubling of `frame_id`) and are received correctly after processing. + */ TEST(cognitive_module_test, startup_simple) { + // Obtain the path to the configuration file std::string pkgpath = ament_index_cpp::get_package_share_directory("cs4home_core"); std::string config_file = pkgpath + "/config/startup_simple_1.yaml"; @@ -318,12 +412,15 @@ TEST(cognitive_module_test, startup_simple) options.arguments( {"--ros-args", "-r", "__node:=cognitive_module_1", "--params-file", config_file}); + // Instantiate the CognitiveModule using the specified configuration file auto cm1 = cs4home_core::CognitiveModule::make_shared(options); ASSERT_EQ(std::string(cm1->get_name()), "cognitive_module_1"); + // Verify the number of parameters loaded from the configuration file auto params = cm1->list_parameters({}, 0); ASSERT_EQ(params.names.size(), 7u); + // Set up publisher and subscriber nodes for testing message processing auto pub_node = rclcpp::Node::make_shared("pub_node"); auto sub_node = rclcpp::Node::make_shared("sub_node"); @@ -340,12 +437,14 @@ TEST(cognitive_module_test, startup_simple) exe.add_node(pub_node); exe.add_node(sub_node); + // Transition the CognitiveModule through the lifecycle states cm1->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE); ASSERT_EQ(cm1->get_current_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); cm1->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE); ASSERT_EQ(cm1->get_current_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE); + // Publish a series of messages to test processing by the CognitiveModule sensor_msgs::msg::Image msg; for (int i = 0; i < 10; i++) { msg.header.frame_id = std::to_string(i); @@ -358,9 +457,11 @@ TEST(cognitive_module_test, startup_simple) exe.spin_some(); } + // Transition the module back to inactive state cm1->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE); ASSERT_EQ(cm1->get_current_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + // Verify that the messages were processed correctly with doubled frame_id values ASSERT_EQ(images.size(), 10); for (int i = 0; i < 10; i++) { ASSERT_EQ(i * 2, std::atoi(images[i].header.frame_id.c_str())); diff --git a/cs4home_core/test/master_test.cpp b/cs4home_core/test/master_test.cpp index 148e58a..e6b8276 100644 --- a/cs4home_core/test/master_test.cpp +++ b/cs4home_core/test/master_test.cpp @@ -12,24 +12,39 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include "ament_index_cpp/get_package_share_directory.hpp" #include "cs4home_core/Flow.hpp" #include "cs4home_core/CognitiveModule.hpp" #include "gtest/gtest.h" - +/** + * @brief Unit test for verifying the creation and structure of Flow instances. + * + * This test checks that `Flow` instances are created correctly with the expected + * sequence of nodes, ensuring that the get_nodes() function returns the correct + * vector of node names. + */ TEST(flow_test, flow_creation) { cs4home_core::Flow flow1({"A", "B", "C", "D"}); cs4home_core::Flow flow2({"A", "B", "C", "E"}); + // Check that the nodes in flow1 match the expected sequence ASSERT_EQ(flow1.get_nodes(), std::vector({"A", "B", "C", "D"})); + // Check that the nodes in flow2 match the expected sequence ASSERT_EQ(flow2.get_nodes(), std::vector({"A", "B", "C", "E"})); } - +/** + * @brief Main function for running all GoogleTest unit tests. + * + * Initializes GoogleTest and ROS 2, then runs all tests defined in the executable. + * + * @param argc Argument count + * @param argv Argument vector + * @return int Test run result (0 if all tests passed, non-zero otherwise) + */ int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); From 3b8ac178a83c5c2517278df816baf04d146f7e55 Mon Sep 17 00:00:00 2001 From: fjrodl Date: Tue, 29 Oct 2024 14:17:57 +0100 Subject: [PATCH 2/9] Minor change --- README.md | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 627ce5a..5e4bf13 100644 --- a/README.md +++ b/README.md @@ -18,7 +18,12 @@ This model is designed as an adaptable solution for a wide variety of robotic sy ## Examples -[![rolling](https://github.com/CoreSenseEU/cs4home_architecture/actions/workflows/rolling.yaml/badge.svg)](https://github.com/CoreSenseEU/cs4home_architecture/actions/workflows/rolling.yaml) +Implementation of the architecture from the Social Testbed point of view -Implementation of the architecture from the Social Testbed point of view + + +## status + +[![rolling](https://github.com/CoreSenseEU/cs4home_architecture/actions/workflows/rolling.yaml/badge.svg)](https://github.com/CoreSenseEU/cs4home_architecture/actions/workflows/rolling.yaml) + From a1409db08339478a8dddbc9bf10ad45cfed398be Mon Sep 17 00:00:00 2001 From: fjrodl Date: Tue, 29 Oct 2024 14:29:35 +0100 Subject: [PATCH 3/9] fixed minor error with override --- cs4home_core/test/DefaultCoupling.cpp | 2 +- cs4home_core/test/DefaultMeta.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cs4home_core/test/DefaultCoupling.cpp b/cs4home_core/test/DefaultCoupling.cpp index 487721d..b4cd4cb 100644 --- a/cs4home_core/test/DefaultCoupling.cpp +++ b/cs4home_core/test/DefaultCoupling.cpp @@ -47,7 +47,7 @@ class DefaultCoupling : public cs4home_core::Coupling * * @return True if configuration is successful. */ - bool configure() override + bool configure() { RCLCPP_DEBUG(parent_->get_logger(), "Coupling configured"); return true; diff --git a/cs4home_core/test/DefaultMeta.cpp b/cs4home_core/test/DefaultMeta.cpp index 2e86d32..04ba2bd 100644 --- a/cs4home_core/test/DefaultMeta.cpp +++ b/cs4home_core/test/DefaultMeta.cpp @@ -47,7 +47,7 @@ class DefaultMeta : public cs4home_core::Meta * * @return True if configuration is successful. */ - bool configure() override + bool configure() { RCLCPP_DEBUG(parent_->get_logger(), "Meta configured"); return true; From 8d3953b4916f5c9d040af432460ad9822fcac6c7 Mon Sep 17 00:00:00 2001 From: fjrodl Date: Tue, 29 Oct 2024 15:03:57 +0100 Subject: [PATCH 4/9] Checking linter issues --- .../include/cs4home_core/Afferent.hpp | 20 ++++++++++++------- .../include/cs4home_core/CognitiveModule.hpp | 2 +- cs4home_core/include/cs4home_core/Core.hpp | 11 ++++++---- .../include/cs4home_core/Coupling.hpp | 8 +++++--- .../include/cs4home_core/Efferent.hpp | 8 +++++--- cs4home_core/include/cs4home_core/Flow.hpp | 2 +- cs4home_core/include/cs4home_core/Master.hpp | 5 +++-- cs4home_core/include/cs4home_core/Meta.hpp | 2 +- cs4home_core/include/cs4home_core/macros.hpp | 2 +- cs4home_core/src/cs4home_core/Afferent.cpp | 2 +- cs4home_core/test/DefaultCoupling.cpp | 4 ++-- cs4home_core/test/DefaultMeta.cpp | 4 ++-- cs4home_core/test/SimpleImageInput.cpp | 3 ++- cs4home_core/test/SimpleImageOutput.cpp | 2 +- 14 files changed, 45 insertions(+), 30 deletions(-) diff --git a/cs4home_core/include/cs4home_core/Afferent.hpp b/cs4home_core/include/cs4home_core/Afferent.hpp index 06e089d..d82a8ce 100644 --- a/cs4home_core/include/cs4home_core/Afferent.hpp +++ b/cs4home_core/include/cs4home_core/Afferent.hpp @@ -120,16 +120,22 @@ class Afferent } protected: - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; /**< Shared pointer to the parent node. */ - std::vector> subs_; /**< List of subscriptions. */ + /** Shared pointer to the parent node. */ + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; + /** List of subscriptions. */ + std::vector> subs_; EfferentProcessMode mode_ {ONDEMAND}; /**< Current processing mode. */ - const size_t MAX_DEFAULT_QUEUE_SIZE = 100; /**< Default maximum queue size. */ - size_t max_queue_size_ {MAX_DEFAULT_QUEUE_SIZE}; /**< Maximum queue size. */ - std::queue> msg_queue_; /**< Queue for serialized messages. */ + /** Default maximum queue size. */ + const size_t MAX_DEFAULT_QUEUE_SIZE = 100; + /** Maximum queue size. */ + size_t max_queue_size_ {MAX_DEFAULT_QUEUE_SIZE}; + /** Queue for serialized messages. */ + std::queue> msg_queue_; - std::function)> callback_; /**< Callback for serialized messages. */ + /** Callback for serialized messages. */ + std::function)> callback_; /** @@ -143,4 +149,4 @@ class Afferent } // namespace cs4home_core -#endif // CS4HOME_CORE__AFFERENT_HPP_ +#endif // CS4HOME_CORE__AFFERENT_HPP_ \ No newline at end of file diff --git a/cs4home_core/include/cs4home_core/CognitiveModule.hpp b/cs4home_core/include/cs4home_core/CognitiveModule.hpp index 57885cd..4594620 100644 --- a/cs4home_core/include/cs4home_core/CognitiveModule.hpp +++ b/cs4home_core/include/cs4home_core/CognitiveModule.hpp @@ -129,4 +129,4 @@ class CognitiveModule : public rclcpp_lifecycle::LifecycleNode // // Register the component with class_loader. // // This acts as a sort of entry point, allowing the component to be discoverable when its library // // is being loaded into a running process. -// RCLCPP_COMPONENTS_REGISTER_NODE(cs4home_core::CognitiveModule) +// RCLCPP_COMPONENTS_REGISTER_NODE(cs4home_core::CognitiveModule) \ No newline at end of file diff --git a/cs4home_core/include/cs4home_core/Core.hpp b/cs4home_core/include/cs4home_core/Core.hpp index 0891691..7959606 100644 --- a/cs4home_core/include/cs4home_core/Core.hpp +++ b/cs4home_core/include/cs4home_core/Core.hpp @@ -73,11 +73,14 @@ class Core void set_efferent(cs4home_core::Efferent::SharedPtr efferent) {efferent_ = efferent;} protected: - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; /**< Shared pointer to the parent lifecycle node. */ - cs4home_core::Afferent::SharedPtr afferent_; /**< Shared pointer to the Afferent component. */ - cs4home_core::Efferent::SharedPtr efferent_; /**< Shared pointer to the Efferent component. */ + /** Shared pointer to the parent lifecycle node. */ + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; + /** Shared pointer to the Afferent component. */ + cs4home_core::Afferent::SharedPtr afferent_; + /** Shared pointer to the Efferent component. */ + cs4home_core::Efferent::SharedPtr efferent_; }; } // namespace cs4home_core -#endif // CS4HOME_CORE__CORE_HPP_ +#endif // CS4HOME_CORE__CORE_HPP_ \ No newline at end of file diff --git a/cs4home_core/include/cs4home_core/Coupling.hpp b/cs4home_core/include/cs4home_core/Coupling.hpp index ff2ec58..3d9f43f 100644 --- a/cs4home_core/include/cs4home_core/Coupling.hpp +++ b/cs4home_core/include/cs4home_core/Coupling.hpp @@ -23,7 +23,8 @@ namespace cs4home_core /** * @class Coupling - * @brief Manages coupling operations within a robotic system, providing lifecycle-aware configuration. + * @brief Manages coupling operations within a robotic system, + * providing lifecycle-aware configuration. */ class Coupling { @@ -43,9 +44,10 @@ class Coupling bool configure(); protected: - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; /**< Shared pointer to the parent lifecycle node. */ + /**< Shared pointer to the parent lifecycle node. */ + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; }; } // namespace cs4home_core -#endif // CS4HOME_CORE__COUPLING_HPP_ +#endif // CS4HOME_CORE__COUPLING_HPP_ \ No newline at end of file diff --git a/cs4home_core/include/cs4home_core/Efferent.hpp b/cs4home_core/include/cs4home_core/Efferent.hpp index 273652b..3d914a9 100644 --- a/cs4home_core/include/cs4home_core/Efferent.hpp +++ b/cs4home_core/include/cs4home_core/Efferent.hpp @@ -70,8 +70,10 @@ class Efferent } protected: - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; /**< Shared pointer to the parent lifecycle node. */ - std::vector> pubs_; /**< List of generic publishers. */ + /**< Shared pointer to the parent lifecycle node. */ + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; + /**< List of generic publishers. */ + std::vector> pubs_; /** * @brief Creates a publisher for a specified topic and message type. @@ -84,4 +86,4 @@ class Efferent } // namespace cs4home_core -#endif // CS4HOME_CORE__EFFERENT_HPP_ +#endif // CS4HOME_CORE__EFFERENT_HPP_ \ No newline at end of file diff --git a/cs4home_core/include/cs4home_core/Flow.hpp b/cs4home_core/include/cs4home_core/Flow.hpp index d500c8e..a93002d 100644 --- a/cs4home_core/include/cs4home_core/Flow.hpp +++ b/cs4home_core/include/cs4home_core/Flow.hpp @@ -64,4 +64,4 @@ class Flow // #include "rclcpp_components/register_node_macro.hpp" // // // Register the component with class_loader. -// // This acts as a sort of entry point, +// // This acts as a sort of entry point, \ No newline at end of file diff --git a/cs4home_core/include/cs4home_core/Master.hpp b/cs4home_core/include/cs4home_core/Master.hpp index f19ea96..c1cb381 100644 --- a/cs4home_core/include/cs4home_core/Master.hpp +++ b/cs4home_core/include/cs4home_core/Master.hpp @@ -87,7 +87,8 @@ class Master : public rclcpp_lifecycle::LifecycleNode CallbackReturnT on_error(const rclcpp_lifecycle::State & state); protected: - std::map cog_modules_; /**< Map of cognitive modules managed by the Master node. */ + /** Map of cognitive modules managed by the Master node. */ + std::map cog_modules_; }; } // namespace cs4home_core @@ -99,4 +100,4 @@ class Master : public rclcpp_lifecycle::LifecycleNode // // Register the component with class_loader. // // This acts as a sort of entry point, allowing the component to be discoverable when its library // // is being loaded into a running process. -// RCLCPP_COMPONENTS_REGISTER_NODE(cs4home_core::Master) +// RCLCPP_COMPONENTS_REGISTER_NODE(cs4home_core::Master) \ No newline at end of file diff --git a/cs4home_core/include/cs4home_core/Meta.hpp b/cs4home_core/include/cs4home_core/Meta.hpp index e7c8a68..a501439 100644 --- a/cs4home_core/include/cs4home_core/Meta.hpp +++ b/cs4home_core/include/cs4home_core/Meta.hpp @@ -49,4 +49,4 @@ class Meta } // namespace cs4home_core -#endif // CS4HOME_CORE__META_HPP_ +#endif // CS4HOME_CORE__META_HPP_ \ No newline at end of file diff --git a/cs4home_core/include/cs4home_core/macros.hpp b/cs4home_core/include/cs4home_core/macros.hpp index d66dbbc..db2d08e 100644 --- a/cs4home_core/include/cs4home_core/macros.hpp +++ b/cs4home_core/include/cs4home_core/macros.hpp @@ -41,4 +41,4 @@ namespace cs4home_core } // namespace cs4home_core -#endif // CS4HOME_CORE__MACROS_HPP_ +#endif // CS4HOME_CORE__MACROS_HPP_ \ No newline at end of file diff --git a/cs4home_core/src/cs4home_core/Afferent.cpp b/cs4home_core/src/cs4home_core/Afferent.cpp index 9003330..9276f17 100644 --- a/cs4home_core/src/cs4home_core/Afferent.cpp +++ b/cs4home_core/src/cs4home_core/Afferent.cpp @@ -100,4 +100,4 @@ Afferent::create_subscriber(const std::string & topic, const std::string & type) return true; } -} // namespace cs4home_core +} // namespace cs4home_core \ No newline at end of file diff --git a/cs4home_core/test/DefaultCoupling.cpp b/cs4home_core/test/DefaultCoupling.cpp index b4cd4cb..e4cce76 100644 --- a/cs4home_core/test/DefaultCoupling.cpp +++ b/cs4home_core/test/DefaultCoupling.cpp @@ -47,7 +47,7 @@ class DefaultCoupling : public cs4home_core::Coupling * * @return True if configuration is successful. */ - bool configure() + bool configure() { RCLCPP_DEBUG(parent_->get_logger(), "Coupling configured"); return true; @@ -55,4 +55,4 @@ class DefaultCoupling : public cs4home_core::Coupling }; /// Registers the DefaultCoupling component with the ROS 2 class loader -CS_REGISTER_COMPONENT(DefaultCoupling) +CS_REGISTER_COMPONENT(DefaultCoupling) \ No newline at end of file diff --git a/cs4home_core/test/DefaultMeta.cpp b/cs4home_core/test/DefaultMeta.cpp index 04ba2bd..5df3400 100644 --- a/cs4home_core/test/DefaultMeta.cpp +++ b/cs4home_core/test/DefaultMeta.cpp @@ -47,7 +47,7 @@ class DefaultMeta : public cs4home_core::Meta * * @return True if configuration is successful. */ - bool configure() + bool configure() { RCLCPP_DEBUG(parent_->get_logger(), "Meta configured"); return true; @@ -55,4 +55,4 @@ class DefaultMeta : public cs4home_core::Meta }; /// Registers the DefaultMeta component with the ROS 2 class loader -CS_REGISTER_COMPONENT(DefaultMeta) +CS_REGISTER_COMPONENT(DefaultMeta) \ No newline at end of file diff --git a/cs4home_core/test/SimpleImageInput.cpp b/cs4home_core/test/SimpleImageInput.cpp index 03fb377..5a6a9a8 100644 --- a/cs4home_core/test/SimpleImageInput.cpp +++ b/cs4home_core/test/SimpleImageInput.cpp @@ -78,7 +78,8 @@ class SimpleImageInput : public cs4home_core::Afferent } private: - std::vector input_topic_names_; /**< List of input topics to subscribe to for images. */ + /**< List of input topics to subscribe to for images. */ + std::vector input_topic_names_; }; /// Registers the SimpleImageInput component with the ROS 2 class loader diff --git a/cs4home_core/test/SimpleImageOutput.cpp b/cs4home_core/test/SimpleImageOutput.cpp index 73ffdf8..ba6bd6a 100644 --- a/cs4home_core/test/SimpleImageOutput.cpp +++ b/cs4home_core/test/SimpleImageOutput.cpp @@ -85,4 +85,4 @@ class SimpleImageOutput : public cs4home_core::Efferent }; /// Registers the SimpleImageOutput component with the ROS 2 class loader -CS_REGISTER_COMPONENT(SimpleImageOutput) +CS_REGISTER_COMPONENT(SimpleImageOutput) \ No newline at end of file From 42e34d754796cc97f52fa81c64ececce80e8d9fc Mon Sep 17 00:00:00 2001 From: fjrodl Date: Thu, 31 Oct 2024 08:16:28 +0100 Subject: [PATCH 5/9] Uncrustified the files --- .../include/cs4home_core/Afferent.hpp | 24 +++++++------- .../include/cs4home_core/CognitiveModule.hpp | 2 +- cs4home_core/include/cs4home_core/Core.hpp | 10 +++--- .../include/cs4home_core/Coupling.hpp | 6 ++-- .../include/cs4home_core/Efferent.hpp | 11 ++++--- cs4home_core/include/cs4home_core/Flow.hpp | 2 +- cs4home_core/include/cs4home_core/Master.hpp | 4 +-- cs4home_core/include/cs4home_core/Meta.hpp | 2 +- cs4home_core/include/cs4home_core/macros.hpp | 6 ++-- cs4home_core/src/cs4home_core/Afferent.cpp | 14 ++++----- .../src/cs4home_core/CognitiveModule.cpp | 4 +-- cs4home_core/src/cs4home_core/Efferent.cpp | 4 +-- cs4home_core/src/cs4home_core/Flow.cpp | 2 +- cs4home_core/test/DefaultCoupling.cpp | 10 +++--- cs4home_core/test/DefaultMeta.cpp | 10 +++--- cs4home_core/test/ImageFilter.cpp | 14 ++++----- cs4home_core/test/ImageFilterCB.cpp | 12 +++---- cs4home_core/test/SimpleImageInput.cpp | 6 ++-- cs4home_core/test/SimpleImageOutput.cpp | 6 ++-- cs4home_core/test/cognitive_module_test.cpp | 31 +++++++++---------- cs4home_core/test/master_test.cpp | 6 ++-- 21 files changed, 94 insertions(+), 92 deletions(-) diff --git a/cs4home_core/include/cs4home_core/Afferent.hpp b/cs4home_core/include/cs4home_core/Afferent.hpp index d82a8ce..30750cc 100644 --- a/cs4home_core/include/cs4home_core/Afferent.hpp +++ b/cs4home_core/include/cs4home_core/Afferent.hpp @@ -25,6 +25,8 @@ #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "rclcpp/rclcpp.hpp" #include "rclcpp/macros.hpp" +#include "rclcpp/serialization.hpp" +#include "rclcpp/create_generic_subscription.hpp" namespace cs4home_core { @@ -59,7 +61,7 @@ class Afferent /** * @brief Sets the processing mode and an optional callback function. - * + * * @param mode Processing mode for handling messages. * @param cb Optional callback function for handling serialized messages in CALLBACK mode. */ @@ -86,12 +88,12 @@ class Afferent */ size_t get_max_queue_size() {return max_queue_size_;} - /** - * @brief Converts a serialized message to a typed message. - * @tparam MessageT Type of the message to deserialize. - * @param msg Serialized message to convert. - * @return A unique pointer to the deserialized message. - */ + /** + * @brief Converts a serialized message to a typed message. + * @tparam MessageT Type of the message to deserialize. + * @param msg Serialized message to convert. + * @return A unique pointer to the deserialized message. + */ template std::unique_ptr get_msg( std::unique_ptr msg) { @@ -121,9 +123,9 @@ class Afferent protected: /** Shared pointer to the parent node. */ - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; /** List of subscriptions. */ - std::vector> subs_; + std::vector> subs_; EfferentProcessMode mode_ {ONDEMAND}; /**< Current processing mode. */ @@ -135,7 +137,7 @@ class Afferent std::queue> msg_queue_; /** Callback for serialized messages. */ - std::function)> callback_; + std::function)> callback_; /** @@ -149,4 +151,4 @@ class Afferent } // namespace cs4home_core -#endif // CS4HOME_CORE__AFFERENT_HPP_ \ No newline at end of file +#endif // CS4HOME_CORE__AFFERENT_HPP_ diff --git a/cs4home_core/include/cs4home_core/CognitiveModule.hpp b/cs4home_core/include/cs4home_core/CognitiveModule.hpp index 4594620..57885cd 100644 --- a/cs4home_core/include/cs4home_core/CognitiveModule.hpp +++ b/cs4home_core/include/cs4home_core/CognitiveModule.hpp @@ -129,4 +129,4 @@ class CognitiveModule : public rclcpp_lifecycle::LifecycleNode // // Register the component with class_loader. // // This acts as a sort of entry point, allowing the component to be discoverable when its library // // is being loaded into a running process. -// RCLCPP_COMPONENTS_REGISTER_NODE(cs4home_core::CognitiveModule) \ No newline at end of file +// RCLCPP_COMPONENTS_REGISTER_NODE(cs4home_core::CognitiveModule) diff --git a/cs4home_core/include/cs4home_core/Core.hpp b/cs4home_core/include/cs4home_core/Core.hpp index 7959606..be7e701 100644 --- a/cs4home_core/include/cs4home_core/Core.hpp +++ b/cs4home_core/include/cs4home_core/Core.hpp @@ -28,7 +28,7 @@ namespace cs4home_core /** * @class Core - * @brief Manages core functionality for a robotic component, including lifecycle transitions + * @brief Manages core functionality for a robotic component, including lifecycle transitions * and connections to afferent and efferent processing components. */ class Core @@ -74,13 +74,13 @@ class Core protected: /** Shared pointer to the parent lifecycle node. */ - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; /** Shared pointer to the Afferent component. */ - cs4home_core::Afferent::SharedPtr afferent_; + cs4home_core::Afferent::SharedPtr afferent_; /** Shared pointer to the Efferent component. */ - cs4home_core::Efferent::SharedPtr efferent_; + cs4home_core::Efferent::SharedPtr efferent_; }; } // namespace cs4home_core -#endif // CS4HOME_CORE__CORE_HPP_ \ No newline at end of file +#endif // CS4HOME_CORE__CORE_HPP_ diff --git a/cs4home_core/include/cs4home_core/Coupling.hpp b/cs4home_core/include/cs4home_core/Coupling.hpp index 3d9f43f..ffaa10d 100644 --- a/cs4home_core/include/cs4home_core/Coupling.hpp +++ b/cs4home_core/include/cs4home_core/Coupling.hpp @@ -23,7 +23,7 @@ namespace cs4home_core /** * @class Coupling - * @brief Manages coupling operations within a robotic system, + * @brief Manages coupling operations within a robotic system, * providing lifecycle-aware configuration. */ class Coupling @@ -45,9 +45,9 @@ class Coupling protected: /**< Shared pointer to the parent lifecycle node. */ - rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; + rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; }; } // namespace cs4home_core -#endif // CS4HOME_CORE__COUPLING_HPP_ \ No newline at end of file +#endif // CS4HOME_CORE__COUPLING_HPP_ diff --git a/cs4home_core/include/cs4home_core/Efferent.hpp b/cs4home_core/include/cs4home_core/Efferent.hpp index 3d914a9..2dea9e3 100644 --- a/cs4home_core/include/cs4home_core/Efferent.hpp +++ b/cs4home_core/include/cs4home_core/Efferent.hpp @@ -21,6 +21,7 @@ #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "rclcpp/macros.hpp" +#include "rclcpp/serialization.hpp" namespace cs4home_core { @@ -49,10 +50,10 @@ class Efferent /** * @brief Publishes a serialized message to all configured publishers. - * + * * This templated method serializes the provided message and broadcasts it to * each publisher in the `pubs_` list. - * + * * @tparam MessageT Type of the message to publish. * @param msg Unique pointer to the message to broadcast. */ @@ -70,9 +71,9 @@ class Efferent } protected: - /**< Shared pointer to the parent lifecycle node. */ + /**< Shared pointer to the parent lifecycle node. */ rclcpp_lifecycle::LifecycleNode::SharedPtr parent_; - /**< List of generic publishers. */ + /**< List of generic publishers. */ std::vector> pubs_; /** @@ -86,4 +87,4 @@ class Efferent } // namespace cs4home_core -#endif // CS4HOME_CORE__EFFERENT_HPP_ \ No newline at end of file +#endif // CS4HOME_CORE__EFFERENT_HPP_ diff --git a/cs4home_core/include/cs4home_core/Flow.hpp b/cs4home_core/include/cs4home_core/Flow.hpp index a93002d..2fdc463 100644 --- a/cs4home_core/include/cs4home_core/Flow.hpp +++ b/cs4home_core/include/cs4home_core/Flow.hpp @@ -64,4 +64,4 @@ class Flow // #include "rclcpp_components/register_node_macro.hpp" // // // Register the component with class_loader. -// // This acts as a sort of entry point, \ No newline at end of file +// // This acts as a sort of entry point, diff --git a/cs4home_core/include/cs4home_core/Master.hpp b/cs4home_core/include/cs4home_core/Master.hpp index c1cb381..c67cfd3 100644 --- a/cs4home_core/include/cs4home_core/Master.hpp +++ b/cs4home_core/include/cs4home_core/Master.hpp @@ -88,7 +88,7 @@ class Master : public rclcpp_lifecycle::LifecycleNode protected: /** Map of cognitive modules managed by the Master node. */ - std::map cog_modules_; + std::map cog_modules_; }; } // namespace cs4home_core @@ -100,4 +100,4 @@ class Master : public rclcpp_lifecycle::LifecycleNode // // Register the component with class_loader. // // This acts as a sort of entry point, allowing the component to be discoverable when its library // // is being loaded into a running process. -// RCLCPP_COMPONENTS_REGISTER_NODE(cs4home_core::Master) \ No newline at end of file +// RCLCPP_COMPONENTS_REGISTER_NODE(cs4home_core::Master) diff --git a/cs4home_core/include/cs4home_core/Meta.hpp b/cs4home_core/include/cs4home_core/Meta.hpp index a501439..e7c8a68 100644 --- a/cs4home_core/include/cs4home_core/Meta.hpp +++ b/cs4home_core/include/cs4home_core/Meta.hpp @@ -49,4 +49,4 @@ class Meta } // namespace cs4home_core -#endif // CS4HOME_CORE__META_HPP_ \ No newline at end of file +#endif // CS4HOME_CORE__META_HPP_ diff --git a/cs4home_core/include/cs4home_core/macros.hpp b/cs4home_core/include/cs4home_core/macros.hpp index db2d08e..c5d19dc 100644 --- a/cs4home_core/include/cs4home_core/macros.hpp +++ b/cs4home_core/include/cs4home_core/macros.hpp @@ -26,10 +26,10 @@ namespace cs4home_core * @def CS_REGISTER_COMPONENT(class_name) * @brief Macro to define a factory function for creating a shared pointer instance * of a component class within the lifecycle node context. - * + * * This macro generates an `extern "C"` factory function named `create_instance` that * returns a shared pointer to the specified class, allowing dynamic component loading. - * + * * @param class_name The name of the class to register as a component. */ #define CS_REGISTER_COMPONENT(class_name) \ @@ -41,4 +41,4 @@ namespace cs4home_core } // namespace cs4home_core -#endif // CS4HOME_CORE__MACROS_HPP_ \ No newline at end of file +#endif // CS4HOME_CORE__MACROS_HPP_ diff --git a/cs4home_core/src/cs4home_core/Afferent.cpp b/cs4home_core/src/cs4home_core/Afferent.cpp index 9276f17..0ab5ab6 100644 --- a/cs4home_core/src/cs4home_core/Afferent.cpp +++ b/cs4home_core/src/cs4home_core/Afferent.cpp @@ -16,7 +16,7 @@ #include "cs4home_core/Afferent.hpp" #include "rclcpp/rclcpp.hpp" - +#include "rclcpp/create_generic_subscription.hpp" namespace cs4home_core { @@ -31,10 +31,10 @@ Afferent::Afferent(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) /** * @brief Sets the operation mode and an optional callback function. - * + * * This function allows configuring the Afferent object with a specific * processing mode and an optional callback to handle serialized messages. - * + * * @param mode The processing mode for the Afferent object. * @param cb A callback function to process serialized messages, used if the mode is CALLBACK. */ @@ -56,14 +56,13 @@ Afferent::set_mode( } - /** * @brief Creates a subscription to a specified topic and type. - * + * * This method sets up a subscription to receive messages on a given topic with * a specified message type. The received messages are either processed through * a callback (if set) or stored in an internal message queue. - * + * * @param topic The topic name to subscribe to. * @param type The type of messages expected on the topic. * @return True if the subscription was created successfully. @@ -95,9 +94,10 @@ Afferent::create_subscriber(const std::string & topic, const std::string & type) } }); + subs_.push_back(sub); return true; } -} // namespace cs4home_core \ No newline at end of file +} // namespace cs4home_core diff --git a/cs4home_core/src/cs4home_core/CognitiveModule.cpp b/cs4home_core/src/cs4home_core/CognitiveModule.cpp index a165b0e..2c5bc01 100644 --- a/cs4home_core/src/cs4home_core/CognitiveModule.cpp +++ b/cs4home_core/src/cs4home_core/CognitiveModule.cpp @@ -179,9 +179,9 @@ CallbackReturnT CognitiveModule::on_error(const rclcpp_lifecycle::State & state) /** * @brief Loads a component dynamically by name. - * + * * Attempts to load the specified component by name from a shared library. - * + * * @tparam T Type of the component to load. * @param name Name of the component. * @param parent Shared pointer to the parent lifecycle node. diff --git a/cs4home_core/src/cs4home_core/Efferent.cpp b/cs4home_core/src/cs4home_core/Efferent.cpp index 2c687e5..feebdaa 100644 --- a/cs4home_core/src/cs4home_core/Efferent.cpp +++ b/cs4home_core/src/cs4home_core/Efferent.cpp @@ -28,10 +28,10 @@ Efferent::Efferent(rclcpp_lifecycle::LifecycleNode::SharedPtr parent) /** * @brief Creates a publisher for a specified topic and message type. - * + * * This function sets up a generic publisher on a given topic, allowing the * Efferent component to send messages of the specified type. - * + * * @param topic The topic name to publish messages to. * @param type The type of messages to publish on the topic. * @return True if the publisher was created successfully. diff --git a/cs4home_core/src/cs4home_core/Flow.cpp b/cs4home_core/src/cs4home_core/Flow.cpp index 0d39627..817317c 100644 --- a/cs4home_core/src/cs4home_core/Flow.cpp +++ b/cs4home_core/src/cs4home_core/Flow.cpp @@ -36,7 +36,7 @@ Flow::Flow(const std::vector & nodes) /** * @brief Prints the sequence of nodes in the flow to the standard output. - * + * * This function outputs each node name in the flow, prefixed by an arrow (->) to * represent the sequence visually. */ diff --git a/cs4home_core/test/DefaultCoupling.cpp b/cs4home_core/test/DefaultCoupling.cpp index e4cce76..c2be7f4 100644 --- a/cs4home_core/test/DefaultCoupling.cpp +++ b/cs4home_core/test/DefaultCoupling.cpp @@ -21,8 +21,8 @@ /** * @class DefaultCoupling * @brief A Coupling component that provides default configuration for coupling-related tasks. - * - * This class extends the Coupling component, initializing with basic configuration. + * + * This class extends the Coupling component, initializing with basic configuration. * It is intended for tasks involving the coordination and interaction of functional components. */ class DefaultCoupling : public cs4home_core::Coupling @@ -42,9 +42,9 @@ class DefaultCoupling : public cs4home_core::Coupling /** * @brief Configures the DefaultCoupling component. - * + * * Logs the configuration step and prepares the component for operation. - * + * * @return True if configuration is successful. */ bool configure() @@ -55,4 +55,4 @@ class DefaultCoupling : public cs4home_core::Coupling }; /// Registers the DefaultCoupling component with the ROS 2 class loader -CS_REGISTER_COMPONENT(DefaultCoupling) \ No newline at end of file +CS_REGISTER_COMPONENT(DefaultCoupling) diff --git a/cs4home_core/test/DefaultMeta.cpp b/cs4home_core/test/DefaultMeta.cpp index 5df3400..ea67afc 100644 --- a/cs4home_core/test/DefaultMeta.cpp +++ b/cs4home_core/test/DefaultMeta.cpp @@ -21,8 +21,8 @@ /** * @class DefaultMeta * @brief A Meta component that provides default configurations for meta-level operations. - * - * This class extends the Meta component, initializing with a basic configuration. + * + * This class extends the Meta component, initializing with a basic configuration. * It is intended for meta-level tasks that require minimal setup. */ class DefaultMeta : public cs4home_core::Meta @@ -42,9 +42,9 @@ class DefaultMeta : public cs4home_core::Meta /** * @brief Configures the DefaultMeta component. - * + * * Logs the configuration step and prepares the component for operation. - * + * * @return True if configuration is successful. */ bool configure() @@ -55,4 +55,4 @@ class DefaultMeta : public cs4home_core::Meta }; /// Registers the DefaultMeta component with the ROS 2 class loader -CS_REGISTER_COMPONENT(DefaultMeta) \ No newline at end of file +CS_REGISTER_COMPONENT(DefaultMeta) diff --git a/cs4home_core/test/ImageFilter.cpp b/cs4home_core/test/ImageFilter.cpp index 0be5c1c..a1c4e2c 100644 --- a/cs4home_core/test/ImageFilter.cpp +++ b/cs4home_core/test/ImageFilter.cpp @@ -47,10 +47,10 @@ class ImageFilter : public cs4home_core::Core /** * @brief Processes an incoming image message by modifying its header. - * + * * The `frame_id` in the image header is converted to an integer, doubled, and set as the new * `frame_id`. The modified message is then sent to the efferent component. - * + * * @param msg Unique pointer to the incoming image message of type `sensor_msgs::msg::Image`. */ void process_in_image(sensor_msgs::msg::Image::UniquePtr msg) @@ -64,7 +64,7 @@ class ImageFilter : public cs4home_core::Core /** * @brief Timer callback function that retrieves an image message and processes it. - * + * * This function is called periodically and attempts to retrieve an image message from the * afferent component. If a message is received, it is passed to `process_in_image`. */ @@ -88,9 +88,9 @@ class ImageFilter : public cs4home_core::Core /** * @brief Activates the ImageFilter component by initializing a timer. - * + * * The timer is set to call `timer_callback` every 50 milliseconds. - * + * * @return True if activation is successful. */ bool activate() override @@ -102,9 +102,9 @@ class ImageFilter : public cs4home_core::Core /** * @brief Deactivates the ImageFilter component by disabling the timer. - * + * * The timer is reset to null, stopping periodic message processing. - * + * * @return True if deactivation is successful. */ bool deactivate() override diff --git a/cs4home_core/test/ImageFilterCB.cpp b/cs4home_core/test/ImageFilterCB.cpp index 7ffee0f..07655af 100644 --- a/cs4home_core/test/ImageFilterCB.cpp +++ b/cs4home_core/test/ImageFilterCB.cpp @@ -46,10 +46,10 @@ class ImageFilterCB : public cs4home_core::Core /** * @brief Processes incoming serialized image messages, applies a simple transformation, and * republishes them. - * + * * The `frame_id` in the image header is converted to an integer, doubled, and set as the new * `frame_id`. The modified message is then sent to the efferent component. - * + * * @param msg Unique pointer to the serialized incoming image message. */ void process_in_image(std::unique_ptr msg) @@ -65,10 +65,10 @@ class ImageFilterCB : public cs4home_core::Core /** * @brief Configures the ImageFilterCB component. - * + * * Sets the afferent component mode to `CALLBACK`, binding the `process_in_image` method to * handle incoming messages. - * + * * @return True if configuration is successful. */ bool configure() override @@ -92,9 +92,9 @@ class ImageFilterCB : public cs4home_core::Core /** * @brief Deactivates the ImageFilterCB component. - * + * * Disables the internal timer by resetting the timer shared pointer to null. - * + * * @return True if deactivation is successful. */ bool deactivate() override diff --git a/cs4home_core/test/SimpleImageInput.cpp b/cs4home_core/test/SimpleImageInput.cpp index 5a6a9a8..4b43f3d 100644 --- a/cs4home_core/test/SimpleImageInput.cpp +++ b/cs4home_core/test/SimpleImageInput.cpp @@ -45,10 +45,10 @@ class SimpleImageInput : public cs4home_core::Afferent /** * @brief Configures the SimpleImageInput by creating subscribers for each specified topic. - * + * * This method retrieves the topic names from the parameter server and attempts to create * a subscription for each topic to receive `sensor_msgs::msg::Image` messages. - * + * * @return True if all subscriptions are created successfully. */ bool configure() override @@ -79,7 +79,7 @@ class SimpleImageInput : public cs4home_core::Afferent private: /**< List of input topics to subscribe to for images. */ - std::vector input_topic_names_; + std::vector input_topic_names_; }; /// Registers the SimpleImageInput component with the ROS 2 class loader diff --git a/cs4home_core/test/SimpleImageOutput.cpp b/cs4home_core/test/SimpleImageOutput.cpp index ba6bd6a..28e3ec0 100644 --- a/cs4home_core/test/SimpleImageOutput.cpp +++ b/cs4home_core/test/SimpleImageOutput.cpp @@ -45,10 +45,10 @@ class SimpleImageOutput : public cs4home_core::Efferent /** * @brief Configures the SimpleImageOutput by creating publishers for each specified topic. - * + * * This method retrieves the topic names from the parameter server and attempts to create * a publisher for each topic to publish `sensor_msgs::msg::Image` messages. - * + * * @return True if all publishers are created successfully. */ bool configure() @@ -85,4 +85,4 @@ class SimpleImageOutput : public cs4home_core::Efferent }; /// Registers the SimpleImageOutput component with the ROS 2 class loader -CS_REGISTER_COMPONENT(SimpleImageOutput) \ No newline at end of file +CS_REGISTER_COMPONENT(SimpleImageOutput) diff --git a/cs4home_core/test/cognitive_module_test.cpp b/cs4home_core/test/cognitive_module_test.cpp index d291a44..58a86c1 100644 --- a/cs4home_core/test/cognitive_module_test.cpp +++ b/cs4home_core/test/cognitive_module_test.cpp @@ -54,10 +54,10 @@ using namespace std::chrono_literals; /** * @test Verifies the functionality of the afferent component in "on demand" mode. - * + * * This test sets up an afferent component to operate in "on demand" mode, where it * retrieves messages from a queue rather than processing them immediately via a callback. - * Messages are published to a topic, and the afferent component is configured to pull + * Messages are published to a topic, and the afferent component is configured to pull * messages from this queue as needed. The test ensures that the messages are correctly * retrieved in order and that once the queue is empty, further retrievals return `nullptr`. */ @@ -114,10 +114,10 @@ TEST(cognitive_module_test, afferent_on_demand) /** * @test Verifies the functionality of the afferent component in callback mode. - * + * * This test sets up an afferent component to operate in callback mode, where it * subscribes to a topic and processes incoming messages by storing them in a vector - * for verification. The component listens to `/image` messages and ensures that all + * for verification. The component listens to `/image` messages and ensures that all * received messages are processed and accessible through the callback mechanism. */ TEST(cognitive_module_test, afferent_on_subscription) @@ -184,11 +184,11 @@ TEST(cognitive_module_test, afferent_on_subscription) } /** * @test Verifies the functionality of the efferent component in publishing messages. - * + * * This test sets up an efferent component to publish messages on a specified topic. * It publishes a series of messages with sequential `frame_id` values and verifies * that these messages are received correctly by a subscriber on the same topic. - * The test ensures that the efferent component is able to correctly configure its + * The test ensures that the efferent component is able to correctly configure its * publishers and transmit messages to external listeners. */ TEST(cognitive_module_test, efferent) @@ -243,12 +243,11 @@ TEST(cognitive_module_test, efferent) } - /** * @test Verifies the core component's behavior when processing incoming messages. - * + * * This test sets up an afferent component to receive messages, a core component - * to process them by doubling the `frame_id` in each message header, and an + * to process them by doubling the `frame_id` in each message header, and an * efferent component to republish the processed messages. The test publishes a * series of messages, each with a sequential `frame_id`, and verifies that the * processed messages in the efferent component have doubled `frame_id` values. @@ -323,11 +322,11 @@ TEST(cognitive_module_test, core) /** * @test Verifies the core component with callback functionality (core_cb) processes incoming * messages and republishes them with doubled `frame_id` values. - * - * This test sets up an afferent component in callback mode to receive messages, a core + * + * This test sets up an afferent component in callback mode to receive messages, a core * component with a callback (`core_cb`) to process the messages by doubling the `frame_id` - * in each message header, and an efferent component to republish the processed messages. - * The test publishes a sequence of messages and verifies that the processed messages have + * in each message header, and an efferent component to republish the processed messages. + * The test publishes a sequence of messages and verifies that the processed messages have * doubled `frame_id` values. */ TEST(cognitive_module_test, core_cb) @@ -400,10 +399,10 @@ TEST(cognitive_module_test, core_cb) /** * @test Tests the initialization and basic functionality of the CognitiveModule using a configuration file. - * + * * This test verifies that the CognitiveModule initializes correctly from a configuration file - * and transitions through the ROS 2 lifecycle states (configure, activate, deactivate). - * It sets up publishers and subscribers to check that messages are processed with expected modifications + * and transitions through the ROS 2 lifecycle states (configure, activate, deactivate). + * It sets up publishers and subscribers to check that messages are processed with expected modifications * (doubling of `frame_id`) and are received correctly after processing. */ TEST(cognitive_module_test, startup_simple) diff --git a/cs4home_core/test/master_test.cpp b/cs4home_core/test/master_test.cpp index e6b8276..53a3361 100644 --- a/cs4home_core/test/master_test.cpp +++ b/cs4home_core/test/master_test.cpp @@ -20,7 +20,7 @@ /** * @brief Unit test for verifying the creation and structure of Flow instances. - * + * * This test checks that `Flow` instances are created correctly with the expected * sequence of nodes, ensuring that the get_nodes() function returns the correct * vector of node names. @@ -38,9 +38,9 @@ TEST(flow_test, flow_creation) /** * @brief Main function for running all GoogleTest unit tests. - * + * * Initializes GoogleTest and ROS 2, then runs all tests defined in the executable. - * + * * @param argc Argument count * @param argv Argument vector * @return int Test run result (0 if all tests passed, non-zero otherwise) From 9bbd5f7063117610d6502003cfe82b23aadb8af5 Mon Sep 17 00:00:00 2001 From: fjrodl Date: Thu, 31 Oct 2024 08:19:17 +0100 Subject: [PATCH 6/9] Added Doxyfile for documentation generation --- Doxyfile | 2658 ++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 2658 insertions(+) create mode 100644 Doxyfile diff --git a/Doxyfile b/Doxyfile new file mode 100644 index 0000000..19b73f8 --- /dev/null +++ b/Doxyfile @@ -0,0 +1,2658 @@ +# Doxyfile 1.9.1 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project. +# +# All text after a double hash (##) is considered a comment and is placed in +# front of the TAG it is preceding. +# +# All text after a single hash (#) is considered a comment and will be ignored. +# The format is: +# TAG = value [value, ...] +# For lists, items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (\" \"). + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the configuration +# file that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# https://www.gnu.org/software/libiconv/ for the list of possible encodings. +# The default value is: UTF-8. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by +# double-quotes, unless you are using Doxywizard) that should identify the +# project for which the documentation is generated. This name is used in the +# title of most generated pages and in a few other places. +# The default value is: My Project. + +PROJECT_NAME = "My Project" + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. This +# could be handy for archiving the generated documentation or if some version +# control system is used. + +PROJECT_NUMBER = + +# Using the PROJECT_BRIEF tag one can provide an optional one line description +# for a project that appears at the top of each page and should give viewer a +# quick idea about the purpose of the project. Keep the description short. + +PROJECT_BRIEF = + +# With the PROJECT_LOGO tag one can specify a logo or an icon that is included +# in the documentation. The maximum height of the logo should not exceed 55 +# pixels and the maximum width should not exceed 200 pixels. Doxygen will copy +# the logo to the output directory. + +PROJECT_LOGO = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path +# into which the generated documentation will be written. If a relative path is +# entered, it will be relative to the location where doxygen was started. If +# left blank the current directory will be used. + +OUTPUT_DIRECTORY = + +# If the CREATE_SUBDIRS tag is set to YES then doxygen will create 4096 sub- +# directories (in 2 levels) under the output directory of each output format and +# will distribute the generated files over these directories. Enabling this +# option can be useful when feeding doxygen a huge amount of source files, where +# putting all generated files in the same directory would otherwise causes +# performance problems for the file system. +# The default value is: NO. + +CREATE_SUBDIRS = NO + +# If the ALLOW_UNICODE_NAMES tag is set to YES, doxygen will allow non-ASCII +# characters to appear in the names of generated files. If set to NO, non-ASCII +# characters will be escaped, for example _xE3_x81_x84 will be used for Unicode +# U+3044. +# The default value is: NO. + +ALLOW_UNICODE_NAMES = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Catalan, Chinese, +# Chinese-Traditional, Croatian, Czech, Danish, Dutch, English (United States), +# Esperanto, Farsi (Persian), Finnish, French, German, Greek, Hungarian, +# Indonesian, Italian, Japanese, Japanese-en (Japanese with English messages), +# Korean, Korean-en (Korean with English messages), Latvian, Lithuanian, +# Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, Romanian, Russian, +# Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, Swedish, Turkish, +# Ukrainian and Vietnamese. +# The default value is: English. + +OUTPUT_LANGUAGE = English + +# The OUTPUT_TEXT_DIRECTION tag is used to specify the direction in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all generated output in the proper direction. +# Possible values are: None, LTR, RTL and Context. +# The default value is: None. + +OUTPUT_TEXT_DIRECTION = None + +# If the BRIEF_MEMBER_DESC tag is set to YES, doxygen will include brief member +# descriptions after the members that are listed in the file and class +# documentation (similar to Javadoc). Set to NO to disable this. +# The default value is: YES. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES, doxygen will prepend the brief +# description of a member or function before the detailed description +# +# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. +# The default value is: YES. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator that is +# used to form the text in various listings. Each string in this list, if found +# as the leading text of the brief description, will be stripped from the text +# and the result, after processing the whole list, is used as the annotated +# text. Otherwise, the brief description is used as-is. If left blank, the +# following values are used ($name is automatically replaced with the name of +# the entity):The $name class, The $name widget, The $name file, is, provides, +# specifies, contains, represents, a, an and the. + +ABBREVIATE_BRIEF = "The $name class" \ + "The $name widget" \ + "The $name file" \ + is \ + provides \ + specifies \ + contains \ + represents \ + a \ + an \ + the + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# doxygen will generate a detailed section even if there is only a brief +# description. +# The default value is: NO. + +ALWAYS_DETAILED_SEC = NO + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. +# The default value is: NO. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES, doxygen will prepend the full path +# before files name in the file list and in the header files. If set to NO the +# shortest path that makes the file name unique will be used +# The default value is: YES. + +FULL_PATH_NAMES = YES + +# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path. +# Stripping is only done if one of the specified strings matches the left-hand +# part of the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the path to +# strip. +# +# Note that you can specify absolute paths here, but also relative paths, which +# will be relative from the directory where doxygen is started. +# This tag requires that the tag FULL_PATH_NAMES is set to YES. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the +# path mentioned in the documentation of a class, which tells the reader which +# header file to include in order to use a class. If left blank only the name of +# the header file containing the class definition is used. Otherwise one should +# specify the list of include paths that are normally passed to the compiler +# using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but +# less readable) file names. This can be useful is your file systems doesn't +# support long names like on DOS, Mac, or CD-ROM. +# The default value is: NO. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the +# first line (until the first dot) of a Javadoc-style comment as the brief +# description. If set to NO, the Javadoc-style will behave just like regular Qt- +# style comments (thus requiring an explicit @brief command for a brief +# description.) +# The default value is: NO. + +JAVADOC_AUTOBRIEF = YES + +# If the JAVADOC_BANNER tag is set to YES then doxygen will interpret a line +# such as +# /*************** +# as being the beginning of a Javadoc-style comment "banner". If set to NO, the +# Javadoc-style will behave just like regular comments and it will not be +# interpreted by doxygen. +# The default value is: NO. + +JAVADOC_BANNER = NO + +# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first +# line (until the first dot) of a Qt-style comment as the brief description. If +# set to NO, the Qt-style will behave just like regular Qt-style comments (thus +# requiring an explicit \brief command for a brief description.) +# The default value is: NO. + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a +# multi-line C++ special comment block (i.e. a block of //! or /// comments) as +# a brief description. This used to be the default behavior. The new default is +# to treat a multi-line C++ comment block as a detailed description. Set this +# tag to YES if you prefer the old behavior instead. +# +# Note that setting this tag to YES also means that rational rose comments are +# not recognized any more. +# The default value is: NO. + +MULTILINE_CPP_IS_BRIEF = NO + +# By default Python docstrings are displayed as preformatted text and doxygen's +# special commands cannot be used. By setting PYTHON_DOCSTRING to NO the +# doxygen's special commands can be used and the contents of the docstring +# documentation blocks is shown as doxygen documentation. +# The default value is: YES. + +PYTHON_DOCSTRING = YES + +# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the +# documentation from any documented member that it re-implements. +# The default value is: YES. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES then doxygen will produce a new +# page for each member. If set to NO, the documentation of a member will be part +# of the file/class/namespace that contains it. +# The default value is: NO. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen +# uses this value to replace tabs by spaces in code fragments. +# Minimum value: 1, maximum value: 16, default value: 4. + +TAB_SIZE = 4 + +# This tag can be used to specify a number of aliases that act as commands in +# the documentation. An alias has the form: +# name=value +# For example adding +# "sideeffect=@par Side Effects:\n" +# will allow you to put the command \sideeffect (or @sideeffect) in the +# documentation, which will result in a user-defined paragraph with heading +# "Side Effects:". You can put \n's in the value part of an alias to insert +# newlines (in the resulting output). You can put ^^ in the value part of an +# alias to insert a newline as if a physical newline was in the original file. +# When you need a literal { or } or , in the value part of an alias you have to +# escape them by means of a backslash (\), this can lead to conflicts with the +# commands \{ and \} for these it is advised to use the version @{ and @} or use +# a double escape (\\{ and \\}) + +ALIASES = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources +# only. Doxygen will then generate output that is more tailored for C. For +# instance, some of the names that are used will be different. The list of all +# members will be omitted, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_FOR_C = NO + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or +# Python sources only. Doxygen will then generate output that is more tailored +# for that language. For instance, namespaces will be presented as packages, +# qualified scopes will look different, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_JAVA = YES + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources. Doxygen will then generate output that is tailored for Fortran. +# The default value is: NO. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for VHDL. +# The default value is: NO. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Set the OPTIMIZE_OUTPUT_SLICE tag to YES if your project consists of Slice +# sources only. Doxygen will then generate output that is more tailored for that +# language. For instance, namespaces will be presented as modules, types will be +# separated into more groups, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_SLICE = NO + +# Doxygen selects the parser to use depending on the extension of the files it +# parses. With this tag you can assign which parser to use for a given +# extension. Doxygen has a built-in mapping, but you can override or extend it +# using this tag. The format is ext=language, where ext is a file extension, and +# language is one of the parsers supported by doxygen: IDL, Java, JavaScript, +# Csharp (C#), C, C++, D, PHP, md (Markdown), Objective-C, Python, Slice, VHDL, +# Fortran (fixed format Fortran: FortranFixed, free formatted Fortran: +# FortranFree, unknown formatted Fortran: Fortran. In the later case the parser +# tries to guess whether the code is fixed or free formatted code, this is the +# default for Fortran type files). For instance to make doxygen treat .inc files +# as Fortran files (default is PHP), and .f files as C (default is Fortran), +# use: inc=Fortran f=C. +# +# Note: For files without extension you can use no_extension as a placeholder. +# +# Note that for custom extensions you also need to set FILE_PATTERNS otherwise +# the files are not read by doxygen. When specifying no_extension you should add +# * to the FILE_PATTERNS. +# +# Note see also the list of default file extension mappings. + +EXTENSION_MAPPING = + +# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments +# according to the Markdown format, which allows for more readable +# documentation. See https://daringfireball.net/projects/markdown/ for details. +# The output of markdown processing is further processed by doxygen, so you can +# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in +# case of backward compatibilities issues. +# The default value is: YES. + +MARKDOWN_SUPPORT = YES + +# When the TOC_INCLUDE_HEADINGS tag is set to a non-zero value, all headings up +# to that level are automatically included in the table of contents, even if +# they do not have an id attribute. +# Note: This feature currently applies only to Markdown headings. +# Minimum value: 0, maximum value: 99, default value: 5. +# This tag requires that the tag MARKDOWN_SUPPORT is set to YES. + +TOC_INCLUDE_HEADINGS = 5 + +# When enabled doxygen tries to link words that correspond to documented +# classes, or namespaces to their corresponding documentation. Such a link can +# be prevented in individual cases by putting a % sign in front of the word or +# globally by setting AUTOLINK_SUPPORT to NO. +# The default value is: YES. + +AUTOLINK_SUPPORT = YES + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should set this +# tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); +# versus func(std::string) {}). This also make the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. +# The default value is: NO. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. +# The default value is: NO. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip (see: +# https://www.riverbankcomputing.com/software/sip/intro) sources only. Doxygen +# will parse them like normal C++ but will assume all classes use public instead +# of private inheritance when no explicit protection keyword is present. +# The default value is: NO. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate +# getter and setter methods for a property. Setting this option to YES will make +# doxygen to replace the get and set methods by a property in the documentation. +# This will only work if the methods are indeed getting or setting a simple +# type. If this is not the case, or you want to show the methods anyway, you +# should set this option to NO. +# The default value is: YES. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. +# The default value is: NO. + +DISTRIBUTE_GROUP_DOC = NO + +# If one adds a struct or class to a group and this option is enabled, then also +# any nested class or struct is added to the same group. By default this option +# is disabled and one has to add nested compounds explicitly via \ingroup. +# The default value is: NO. + +GROUP_NESTED_COMPOUNDS = NO + +# Set the SUBGROUPING tag to YES to allow class member groups of the same type +# (for instance a group of public functions) to be put as a subgroup of that +# type (e.g. under the Public Functions section). Set it to NO to prevent +# subgrouping. Alternatively, this can be done per class using the +# \nosubgrouping command. +# The default value is: YES. + +SUBGROUPING = YES + +# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions +# are shown inside the group in which they are included (e.g. using \ingroup) +# instead of on a separate page (for HTML and Man pages) or section (for LaTeX +# and RTF). +# +# Note that this feature does not work in combination with +# SEPARATE_MEMBER_PAGES. +# The default value is: NO. + +INLINE_GROUPED_CLASSES = NO + +# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions +# with only public data fields or simple typedef fields will be shown inline in +# the documentation of the scope in which they are defined (i.e. file, +# namespace, or group documentation), provided this scope is documented. If set +# to NO, structs, classes, and unions are shown on a separate page (for HTML and +# Man pages) or section (for LaTeX and RTF). +# The default value is: NO. + +INLINE_SIMPLE_STRUCTS = NO + +# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or +# enum is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically be +# useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. +# The default value is: NO. + +TYPEDEF_HIDES_STRUCT = NO + +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can be +# an expensive process and often the same symbol appears multiple times in the +# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small +# doxygen will become slower. If the cache is too large, memory is wasted. The +# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range +# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 +# symbols. At the end of a run doxygen will report the cache usage and suggest +# the optimal cache size from a speed point of view. +# Minimum value: 0, maximum value: 9, default value: 0. + +LOOKUP_CACHE_SIZE = 0 + +# The NUM_PROC_THREADS specifies the number threads doxygen is allowed to use +# during processing. When set to 0 doxygen will based this on the number of +# cores available in the system. You can set it explicitly to a value larger +# than 0 to get more control over the balance between CPU load and processing +# speed. At this moment only the input processing can be done using multiple +# threads. Since this is still an experimental feature the default is set to 1, +# which efficively disables parallel processing. Please report any issues you +# encounter. Generating dot graphs in parallel is controlled by the +# DOT_NUM_THREADS setting. +# Minimum value: 0, maximum value: 32, default value: 1. + +NUM_PROC_THREADS = 1 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES, doxygen will assume all entities in +# documentation are documented, even if no documentation was available. Private +# class members and static file members will be hidden unless the +# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES. +# Note: This will also disable the warnings about undocumented members that are +# normally produced when WARNINGS is set to YES. +# The default value is: NO. + +EXTRACT_ALL = YES + +# If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will +# be included in the documentation. +# The default value is: NO. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_PRIV_VIRTUAL tag is set to YES, documented private virtual +# methods of a class will be included in the documentation. +# The default value is: NO. + +EXTRACT_PRIV_VIRTUAL = NO + +# If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal +# scope will be included in the documentation. +# The default value is: NO. + +EXTRACT_PACKAGE = NO + +# If the EXTRACT_STATIC tag is set to YES, all static members of a file will be +# included in the documentation. +# The default value is: NO. + +EXTRACT_STATIC = NO + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES, classes (and structs) defined +# locally in source files will be included in the documentation. If set to NO, +# only classes defined in header files are included. Does not have any effect +# for Java sources. +# The default value is: YES. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. If set to YES, local methods, +# which are defined in the implementation section but not in the interface are +# included in the documentation. If set to NO, only methods in the interface are +# included. +# The default value is: NO. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base name of +# the file that contains the anonymous namespace. By default anonymous namespace +# are hidden. +# The default value is: NO. + +EXTRACT_ANON_NSPACES = NO + +# If this flag is set to YES, the name of an unnamed parameter in a declaration +# will be determined by the corresponding definition. By default unnamed +# parameters remain unnamed in the output. +# The default value is: YES. + +RESOLVE_UNNAMED_PARAMS = YES + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all +# undocumented members inside documented classes or files. If set to NO these +# members will be included in the various overviews, but no documentation +# section is generated. This option has no effect if EXTRACT_ALL is enabled. +# The default value is: NO. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. If set +# to NO, these classes will be included in the various overviews. This option +# has no effect if EXTRACT_ALL is enabled. +# The default value is: NO. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend +# declarations. If set to NO, these declarations will be included in the +# documentation. +# The default value is: NO. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any +# documentation blocks found inside the body of a function. If set to NO, these +# blocks will be appended to the function's detailed documentation block. +# The default value is: NO. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation that is typed after a +# \internal command is included. If the tag is set to NO then the documentation +# will be excluded. Set it to YES to include the internal documentation. +# The default value is: NO. + +INTERNAL_DOCS = NO + +# With the correct setting of option CASE_SENSE_NAMES doxygen will better be +# able to match the capabilities of the underlying filesystem. In case the +# filesystem is case sensitive (i.e. it supports files in the same directory +# whose names only differ in casing), the option must be set to YES to properly +# deal with such files in case they appear in the input. For filesystems that +# are not case sensitive the option should be be set to NO to properly deal with +# output files written for symbols that only differ in casing, such as for two +# classes, one named CLASS and the other named Class, and to also support +# references to files without having to specify the exact matching casing. On +# Windows (including Cygwin) and MacOS, users should typically set this option +# to NO, whereas on Linux or other Unix flavors it should typically be set to +# YES. +# The default value is: system dependent. + +CASE_SENSE_NAMES = YES + +# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with +# their full class and namespace scopes in the documentation. If set to YES, the +# scope will be hidden. +# The default value is: NO. + +HIDE_SCOPE_NAMES = YES + +# If the HIDE_COMPOUND_REFERENCE tag is set to NO (default) then doxygen will +# append additional text to a page's title, such as Class Reference. If set to +# YES the compound reference will be hidden. +# The default value is: NO. + +HIDE_COMPOUND_REFERENCE= NO + +# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of +# the files that are included by a file in the documentation of that file. +# The default value is: YES. + +SHOW_INCLUDE_FILES = YES + +# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each +# grouped member an include statement to the documentation, telling the reader +# which file to include in order to use the member. +# The default value is: NO. + +SHOW_GROUPED_MEMB_INC = NO + +# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include +# files with double quotes in the documentation rather than with sharp brackets. +# The default value is: NO. + +FORCE_LOCAL_INCLUDES = NO + +# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the +# documentation for inline members. +# The default value is: YES. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the +# (detailed) documentation of file and class members alphabetically by member +# name. If set to NO, the members will appear in declaration order. +# The default value is: YES. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief +# descriptions of file, namespace and class members alphabetically by member +# name. If set to NO, the members will appear in declaration order. Note that +# this will also influence the order of the classes in the class list. +# The default value is: NO. + +SORT_BRIEF_DOCS = YES + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the +# (brief and detailed) documentation of class members so that constructors and +# destructors are listed first. If set to NO the constructors will appear in the +# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS. +# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief +# member documentation. +# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting +# detailed member documentation. +# The default value is: NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy +# of group names into alphabetical order. If set to NO the group names will +# appear in their defined order. +# The default value is: NO. + +SORT_GROUP_NAMES = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by +# fully-qualified names, including namespaces. If set to NO, the class list will +# be sorted only by class name, not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the alphabetical +# list. +# The default value is: NO. + +SORT_BY_SCOPE_NAME = NO + +# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper +# type resolution of all parameters of a function it will reject a match between +# the prototype and the implementation of a member function even if there is +# only one candidate or it is obvious which candidate to choose by doing a +# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still +# accept a match between prototype and implementation in such cases. +# The default value is: NO. + +STRICT_PROTO_MATCHING = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or disable (NO) the todo +# list. This list is created by putting \todo commands in the documentation. +# The default value is: YES. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or disable (NO) the test +# list. This list is created by putting \test commands in the documentation. +# The default value is: YES. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or disable (NO) the bug +# list. This list is created by putting \bug commands in the documentation. +# The default value is: YES. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or disable (NO) +# the deprecated list. This list is created by putting \deprecated commands in +# the documentation. +# The default value is: YES. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional documentation +# sections, marked by \if ... \endif and \cond +# ... \endcond blocks. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the +# initial value of a variable or macro / define can have for it to appear in the +# documentation. If the initializer consists of more lines than specified here +# it will be hidden. Use a value of 0 to hide initializers completely. The +# appearance of the value of individual variables and macros / defines can be +# controlled using \showinitializer or \hideinitializer command in the +# documentation regardless of this setting. +# Minimum value: 0, maximum value: 10000, default value: 30. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at +# the bottom of the documentation of classes and structs. If set to YES, the +# list will mention the files that were used to generate the documentation. +# The default value is: YES. + +SHOW_USED_FILES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This +# will remove the Files entry from the Quick Index and from the Folder Tree View +# (if specified). +# The default value is: YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces +# page. This will remove the Namespaces entry from the Quick Index and from the +# Folder Tree View (if specified). +# The default value is: YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command command input-file, where command is the value of the +# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided +# by doxygen. Whatever the program writes to standard output is used as the file +# version. For an example see the documentation. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed +# by doxygen. The layout file controls the global structure of the generated +# output files in an output format independent way. To create the layout file +# that represents doxygen's defaults, run doxygen with the -l option. You can +# optionally specify a file name after the option, if omitted DoxygenLayout.xml +# will be used as the name of the layout file. +# +# Note that if you run doxygen from a directory containing a file called +# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE +# tag is left empty. + +LAYOUT_FILE = + +# The CITE_BIB_FILES tag can be used to specify one or more bib files containing +# the reference definitions. This must be a list of .bib files. The .bib +# extension is automatically appended if omitted. This requires the bibtex tool +# to be installed. See also https://en.wikipedia.org/wiki/BibTeX for more info. +# For LaTeX the style of the bibliography can be controlled using +# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the +# search path. See also \cite for info how to create references. + +CITE_BIB_FILES = + +#--------------------------------------------------------------------------- +# Configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated to +# standard output by doxygen. If QUIET is set to YES this implies that the +# messages are off. +# The default value is: NO. + +QUIET = NO + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated to standard error (stderr) by doxygen. If WARNINGS is set to YES +# this implies that the warnings are on. +# +# Tip: Turn warnings on while writing the documentation. +# The default value is: YES. + +WARNINGS = YES + +# If the WARN_IF_UNDOCUMENTED tag is set to YES then doxygen will generate +# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag +# will automatically be disabled. +# The default value is: YES. + +WARN_IF_UNDOCUMENTED = YES + +# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some parameters +# in a documented function, or documenting parameters that don't exist or using +# markup commands wrongly. +# The default value is: YES. + +WARN_IF_DOC_ERROR = YES + +# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that +# are documented, but have no documentation for their parameters or return +# value. If set to NO, doxygen will only warn about wrong or incomplete +# parameter documentation, but not about the absence of documentation. If +# EXTRACT_ALL is set to YES then this flag will automatically be disabled. +# The default value is: NO. + +WARN_NO_PARAMDOC = NO + +# If the WARN_AS_ERROR tag is set to YES then doxygen will immediately stop when +# a warning is encountered. If the WARN_AS_ERROR tag is set to FAIL_ON_WARNINGS +# then doxygen will continue running as if WARN_AS_ERROR tag is set to NO, but +# at the end of the doxygen process doxygen will return with a non-zero status. +# Possible values are: NO, YES and FAIL_ON_WARNINGS. +# The default value is: NO. + +WARN_AS_ERROR = NO + +# The WARN_FORMAT tag determines the format of the warning messages that doxygen +# can produce. The string should contain the $file, $line, and $text tags, which +# will be replaced by the file and line number from which the warning originated +# and the warning text. Optionally the format may contain $version, which will +# be replaced by the version of the file (if it could be obtained via +# FILE_VERSION_FILTER) +# The default value is: $file:$line: $text. + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning and error +# messages should be written. If left blank the output is written to standard +# error (stderr). + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# Configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag is used to specify the files and/or directories that contain +# documented source files. You may enter file names like myfile.cpp or +# directories like /usr/src/myproject. Separate the files or directories with +# spaces. See also FILE_PATTERNS and EXTENSION_MAPPING +# Note: If this tag is empty the current directory is searched. + +INPUT = ./ + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses +# libiconv (or the iconv built into libc) for the transcoding. See the libiconv +# documentation (see: +# https://www.gnu.org/software/libiconv/) for the list of possible encodings. +# The default value is: UTF-8. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and +# *.h) to filter out the source-files in the directories. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# read by doxygen. +# +# Note the list of default checked file patterns might differ from the list of +# default file extension mappings. +# +# If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp, +# *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, +# *.hh, *.hxx, *.hpp, *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, +# *.m, *.markdown, *.md, *.mm, *.dox (to be provided as doxygen C comment), +# *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f18, *.f, *.for, *.vhd, *.vhdl, +# *.ucf, *.qsf and *.ice. + +FILE_PATTERNS = *.c \ + *.cc \ + *.cxx \ + *.cpp \ + *.c++ \ + *.java \ + *.ii \ + *.ixx \ + *.ipp \ + *.i++ \ + *.inl \ + *.idl \ + *.ddl \ + *.odl \ + *.h \ + *.hh \ + *.hxx \ + *.hpp \ + *.h++ \ + *.cs \ + *.d \ + *.php \ + *.php4 \ + *.php5 \ + *.phtml \ + *.inc \ + *.m \ + *.markdown \ + *.md \ + *.mm \ + *.dox \ + *.py \ + *.pyw \ + *.f90 \ + *.f95 \ + *.f03 \ + *.f08 \ + *.f18 \ + *.f \ + *.for \ + *.vhd \ + *.vhdl \ + *.ucf \ + *.qsf \ + *.ice + +# The RECURSIVE tag can be used to specify whether or not subdirectories should +# be searched for input files as well. +# The default value is: NO. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should be +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. +# +# Note that relative paths are relative to the directory from which doxygen is +# run. + +EXCLUDE = + +# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or +# directories that are symbolic links (a Unix file system feature) are excluded +# from the input. +# The default value is: NO. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. +# +# Note that the wildcards are matched against the file with absolute path, so to +# exclude all test directories for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# AClass::ANamespace, ANamespace::*Test +# +# Note that the wildcards are matched against the file with absolute path, so to +# exclude all test directories use the pattern */test/* + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or directories +# that contain example code fragments that are included (see the \include +# command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and +# *.h) to filter out the source-files in the directories. If left blank all +# files are included. + +EXAMPLE_PATTERNS = * + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude commands +# irrespective of the value of the RECURSIVE tag. +# The default value is: NO. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or directories +# that contain images that are to be included in the documentation (see the +# \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command: +# +# +# +# where is the value of the INPUT_FILTER tag, and is the +# name of an input file. Doxygen will then use the output that the filter +# program writes to standard output. If FILTER_PATTERNS is specified, this tag +# will be ignored. +# +# Note that the filter must not add or remove lines; it is applied before the +# code is scanned, but not when the output code is generated. If lines are added +# or removed, the anchors will not be placed correctly. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# properly processed by doxygen. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. The filters are a list of the form: pattern=filter +# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how +# filters are used. If the FILTER_PATTERNS tag is empty or if none of the +# patterns match the file name, INPUT_FILTER is applied. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# properly processed by doxygen. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will also be used to filter the input files that are used for +# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES). +# The default value is: NO. + +FILTER_SOURCE_FILES = NO + +# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file +# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and +# it is also possible to disable source filtering for a specific pattern using +# *.ext= (so without naming a filter). +# This tag requires that the tag FILTER_SOURCE_FILES is set to YES. + +FILTER_SOURCE_PATTERNS = + +# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that +# is part of the input, its contents will be placed on the main page +# (index.html). This can be useful if you have a project on for instance GitHub +# and want to reuse the introduction page also for the doxygen output. + +USE_MDFILE_AS_MAINPAGE = + +#--------------------------------------------------------------------------- +# Configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will be +# generated. Documented entities will be cross-referenced with these sources. +# +# Note: To get rid of all source code in the generated output, make sure that +# also VERBATIM_HEADERS is set to NO. +# The default value is: NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body of functions, +# classes and enums directly into the documentation. +# The default value is: NO. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any +# special comment blocks from generated source code fragments. Normal C, C++ and +# Fortran comments will always remain visible. +# The default value is: YES. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES then for each documented +# entity all documented functions referencing it will be listed. +# The default value is: NO. + +REFERENCED_BY_RELATION = NO + +# If the REFERENCES_RELATION tag is set to YES then for each documented function +# all documented entities called/used by that function will be listed. +# The default value is: NO. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set +# to YES then the hyperlinks from functions in REFERENCES_RELATION and +# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will +# link to the documentation. +# The default value is: YES. + +REFERENCES_LINK_SOURCE = YES + +# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the +# source code will show a tooltip with additional information such as prototype, +# brief description and links to the definition and documentation. Since this +# will make the HTML file larger and loading of large files a bit slower, you +# can opt to disable this feature. +# The default value is: YES. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +SOURCE_TOOLTIPS = YES + +# If the USE_HTAGS tag is set to YES then the references to source code will +# point to the HTML generated by the htags(1) tool instead of doxygen built-in +# source browser. The htags tool is part of GNU's global source tagging system +# (see https://www.gnu.org/software/global/global.html). You will need version +# 4.8.6 or higher. +# +# To use it do the following: +# - Install the latest version of global +# - Enable SOURCE_BROWSER and USE_HTAGS in the configuration file +# - Make sure the INPUT points to the root of the source tree +# - Run doxygen as normal +# +# Doxygen will invoke htags (and that will in turn invoke gtags), so these +# tools must be available from the command line (i.e. in the search path). +# +# The result: instead of the source browser generated by doxygen, the links to +# source code will now point to the output of htags. +# The default value is: NO. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a +# verbatim copy of the header file for each class for which an include is +# specified. Set to NO to disable this. +# See also: Section \class. +# The default value is: YES. + +VERBATIM_HEADERS = YES + +# If the CLANG_ASSISTED_PARSING tag is set to YES then doxygen will use the +# clang parser (see: +# http://clang.llvm.org/) for more accurate parsing at the cost of reduced +# performance. This can be particularly helpful with template rich C++ code for +# which doxygen's built-in parser lacks the necessary type information. +# Note: The availability of this option depends on whether or not doxygen was +# generated with the -Duse_libclang=ON option for CMake. +# The default value is: NO. + +CLANG_ASSISTED_PARSING = NO + +# If clang assisted parsing is enabled and the CLANG_ADD_INC_PATHS tag is set to +# YES then doxygen will add the directory of each input to the include path. +# The default value is: YES. + +CLANG_ADD_INC_PATHS = YES + +# If clang assisted parsing is enabled you can provide the compiler with command +# line options that you would normally use when invoking the compiler. Note that +# the include paths will already be set by doxygen for the files and directories +# specified with INPUT and INCLUDE_PATH. +# This tag requires that the tag CLANG_ASSISTED_PARSING is set to YES. + +CLANG_OPTIONS = + +# If clang assisted parsing is enabled you can provide the clang parser with the +# path to the directory containing a file called compile_commands.json. This +# file is the compilation database (see: +# http://clang.llvm.org/docs/HowToSetupToolingForLLVM.html) containing the +# options used when the source files were built. This is equivalent to +# specifying the -p option to a clang tool, such as clang-check. These options +# will then be passed to the parser. Any options specified with CLANG_OPTIONS +# will be added as well. +# Note: The availability of this option depends on whether or not doxygen was +# generated with the -Duse_libclang=ON option for CMake. + +CLANG_DATABASE_PATH = + +#--------------------------------------------------------------------------- +# Configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all +# compounds will be generated. Enable this if the project contains a lot of +# classes, structs, unions or interfaces. +# The default value is: YES. + +ALPHABETICAL_INDEX = YES + +# In case all classes in a project start with a common prefix, all classes will +# be put under the same header in the alphabetical index. The IGNORE_PREFIX tag +# can be used to specify a prefix (or a list of prefixes) that should be ignored +# while generating the index headers. +# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES, doxygen will generate HTML output +# The default value is: YES. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a +# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of +# it. +# The default directory is: html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each +# generated HTML page (for example: .htm, .php, .asp). +# The default value is: .html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a user-defined HTML header file for +# each generated HTML page. If the tag is left blank doxygen will generate a +# standard header. +# +# To get valid HTML the header file that includes any scripts and style sheets +# that doxygen needs, which is dependent on the configuration options used (e.g. +# the setting GENERATE_TREEVIEW). It is highly recommended to start with a +# default header using +# doxygen -w html new_header.html new_footer.html new_stylesheet.css +# YourConfigFile +# and then modify the file new_header.html. See also section "Doxygen usage" +# for information on how to generate the default header that doxygen normally +# uses. +# Note: The header is subject to change so you typically have to regenerate the +# default header when upgrading to a newer version of doxygen. For a description +# of the possible markers and block names see the documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each +# generated HTML page. If the tag is left blank doxygen will generate a standard +# footer. See HTML_HEADER for more information on how to generate a default +# footer and what special commands can be used inside the footer. See also +# section "Doxygen usage" for information on how to generate the default footer +# that doxygen normally uses. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style +# sheet that is used by each HTML page. It can be used to fine-tune the look of +# the HTML output. If left blank doxygen will generate a default style sheet. +# See also section "Doxygen usage" for information on how to generate the style +# sheet that doxygen normally uses. +# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as +# it is more robust and this tag (HTML_STYLESHEET) will in the future become +# obsolete. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_STYLESHEET = + +# The HTML_EXTRA_STYLESHEET tag can be used to specify additional user-defined +# cascading style sheets that are included after the standard style sheets +# created by doxygen. Using this option one can overrule certain style aspects. +# This is preferred over using HTML_STYLESHEET since it does not replace the +# standard style sheet and is therefore more robust against future updates. +# Doxygen will copy the style sheet files to the output directory. +# Note: The order of the extra style sheet files is of importance (e.g. the last +# style sheet in the list overrules the setting of the previous ones in the +# list). For an example see the documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_STYLESHEET = + +# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the HTML output directory. Note +# that these files will be copied to the base HTML output directory. Use the +# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these +# files. In the HTML_STYLESHEET file, use the file name only. Also note that the +# files will be copied as-is; there are no commands or markers available. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_FILES = + +# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen +# will adjust the colors in the style sheet and background images according to +# this color. Hue is specified as an angle on a colorwheel, see +# https://en.wikipedia.org/wiki/Hue for more information. For instance the value +# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 +# purple, and 360 is red again. +# Minimum value: 0, maximum value: 359, default value: 220. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_HUE = 220 + +# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors +# in the HTML output. For a value of 0 the output will use grayscales only. A +# value of 255 will produce the most vivid colors. +# Minimum value: 0, maximum value: 255, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_SAT = 100 + +# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the +# luminance component of the colors in the HTML output. Values below 100 +# gradually make the output lighter, whereas values above 100 make the output +# darker. The value divided by 100 is the actual gamma applied, so 80 represents +# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not +# change the gamma. +# Minimum value: 40, maximum value: 240, default value: 80. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_GAMMA = 80 + +# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML +# page will contain the date and time when the page was generated. Setting this +# to YES can help to show when doxygen was last run and thus if the +# documentation is up to date. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_TIMESTAMP = NO + +# If the HTML_DYNAMIC_MENUS tag is set to YES then the generated HTML +# documentation will contain a main index with vertical navigation menus that +# are dynamically created via JavaScript. If disabled, the navigation index will +# consists of multiple levels of tabs that are statically embedded in every HTML +# page. Disable this option to support browsers that do not have JavaScript, +# like the Qt help browser. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_DYNAMIC_MENUS = YES + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_DYNAMIC_SECTIONS = NO + +# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries +# shown in the various tree structured indices initially; the user can expand +# and collapse entries dynamically later on. Doxygen will expand the tree to +# such a level that at most the specified number of entries are visible (unless +# a fully collapsed tree already exceeds this amount). So setting the number of +# entries 1 will produce a full collapsed tree by default. 0 is a special value +# representing an infinite number of entries and will result in a full expanded +# tree by default. +# Minimum value: 0, maximum value: 9999, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_INDEX_NUM_ENTRIES = 100 + +# If the GENERATE_DOCSET tag is set to YES, additional index files will be +# generated that can be used as input for Apple's Xcode 3 integrated development +# environment (see: +# https://developer.apple.com/xcode/), introduced with OSX 10.5 (Leopard). To +# create a documentation set, doxygen will generate a Makefile in the HTML +# output directory. Running make will produce the docset in that directory and +# running make install will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at +# startup. See https://developer.apple.com/library/archive/featuredarticles/Doxy +# genXcode/_index.html for more information. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_DOCSET = NO + +# This tag determines the name of the docset feed. A documentation feed provides +# an umbrella under which multiple documentation sets from a single provider +# (such as a company or product suite) can be grouped. +# The default value is: Doxygen generated docs. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# This tag specifies a string that should uniquely identify the documentation +# set bundle. This should be a reverse domain-name style string, e.g. +# com.mycompany.MyDocSet. Doxygen will append .docset to the name. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify +# the documentation publisher. This should be a reverse domain-name style +# string, e.g. com.mycompany.MyDocSet.documentation. +# The default value is: org.doxygen.Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_ID = org.doxygen.Publisher + +# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher. +# The default value is: Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_NAME = Publisher + +# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three +# additional HTML index files: index.hhp, index.hhc, and index.hhk. The +# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop +# (see: +# https://www.microsoft.com/en-us/download/details.aspx?id=21138) on Windows. +# +# The HTML Help Workshop contains a compiler that can convert all HTML output +# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML +# files are now used as the Windows 98 help format, and will replace the old +# Windows help format (.hlp) on all Windows platforms in the future. Compressed +# HTML files also contain an index, a table of contents, and you can search for +# words in the documentation. The HTML workshop also contains a viewer for +# compressed HTML files. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_HTMLHELP = NO + +# The CHM_FILE tag can be used to specify the file name of the resulting .chm +# file. You can add a path in front of the file if the result should not be +# written to the html output directory. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_FILE = + +# The HHC_LOCATION tag can be used to specify the location (absolute path +# including file name) of the HTML help compiler (hhc.exe). If non-empty, +# doxygen will try to run the HTML help compiler on the generated index.hhp. +# The file has to be specified with full path. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +HHC_LOCATION = + +# The GENERATE_CHI flag controls if a separate .chi index file is generated +# (YES) or that it should be included in the main .chm file (NO). +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +GENERATE_CHI = NO + +# The CHM_INDEX_ENCODING is used to encode HtmlHelp index (hhk), content (hhc) +# and project file content. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_INDEX_ENCODING = + +# The BINARY_TOC flag controls whether a binary table of contents is generated +# (YES) or a normal table of contents (NO) in the .chm file. Furthermore it +# enables the Previous and Next buttons. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members to +# the table of contents of the HTML help documentation and to the tree view. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and +# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that +# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help +# (.qch) of the generated HTML documentation. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify +# the file name of the resulting .qch file. The path specified is relative to +# the HTML output folder. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help +# Project output. For more information please see Qt Help Project / Namespace +# (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace). +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_NAMESPACE = org.doxygen.Project + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt +# Help Project output. For more information please see Qt Help Project / Virtual +# Folders (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual-folders). +# The default value is: doc. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_VIRTUAL_FOLDER = doc + +# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom +# filter to add. For more information please see Qt Help Project / Custom +# Filters (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the +# custom filter to add. For more information please see Qt Help Project / Custom +# Filters (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this +# project's filter section matches. Qt Help Project / Filter Attributes (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#filter-attributes). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_SECT_FILTER_ATTRS = + +# The QHG_LOCATION tag can be used to specify the location (absolute path +# including file name) of Qt's qhelpgenerator. If non-empty doxygen will try to +# run qhelpgenerator on the generated .qhp file. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHG_LOCATION = + +# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be +# generated, together with the HTML files, they form an Eclipse help plugin. To +# install this plugin and make it available under the help contents menu in +# Eclipse, the contents of the directory containing the HTML and XML files needs +# to be copied into the plugins directory of eclipse. The name of the directory +# within the plugins directory should be the same as the ECLIPSE_DOC_ID value. +# After copying Eclipse needs to be restarted before the help appears. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_ECLIPSEHELP = NO + +# A unique identifier for the Eclipse help plugin. When installing the plugin +# the directory name containing the HTML and XML files should also have this +# name. Each documentation set should have its own identifier. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES. + +ECLIPSE_DOC_ID = org.doxygen.Project + +# If you want full control over the layout of the generated HTML pages it might +# be necessary to disable the index and replace it with your own. The +# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top +# of each HTML page. A value of NO enables the index and the value YES disables +# it. Since the tabs in the index contain the same information as the navigation +# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +DISABLE_INDEX = NO + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. If the tag +# value is set to YES, a side panel will be generated containing a tree-like +# index structure (just like the one that is generated for HTML Help). For this +# to work a browser that supports JavaScript, DHTML, CSS and frames is required +# (i.e. any modern browser). Windows users are probably better off using the +# HTML help feature. Via custom style sheets (see HTML_EXTRA_STYLESHEET) one can +# further fine-tune the look of the index. As an example, the default style +# sheet generated by doxygen has an example that shows how to put an image at +# the root of the tree instead of the PROJECT_NAME. Since the tree basically has +# the same information as the tab index, you could consider setting +# DISABLE_INDEX to YES when enabling this option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_TREEVIEW = NO + +# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that +# doxygen will group on one line in the generated HTML documentation. +# +# Note that a value of 0 will completely suppress the enum values from appearing +# in the overview section. +# Minimum value: 0, maximum value: 20, default value: 4. +# This tag requires that the tag GENERATE_HTML is set to YES. + +ENUM_VALUES_PER_LINE = 4 + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used +# to set the initial width (in pixels) of the frame in which the tree is shown. +# Minimum value: 0, maximum value: 1500, default value: 250. +# This tag requires that the tag GENERATE_HTML is set to YES. + +TREEVIEW_WIDTH = 250 + +# If the EXT_LINKS_IN_WINDOW option is set to YES, doxygen will open links to +# external symbols imported via tag files in a separate window. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +EXT_LINKS_IN_WINDOW = NO + +# If the HTML_FORMULA_FORMAT option is set to svg, doxygen will use the pdf2svg +# tool (see https://github.com/dawbarton/pdf2svg) or inkscape (see +# https://inkscape.org) to generate formulas as SVG images instead of PNGs for +# the HTML output. These images will generally look nicer at scaled resolutions. +# Possible values are: png (the default) and svg (looks nicer but requires the +# pdf2svg or inkscape tool). +# The default value is: png. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FORMULA_FORMAT = png + +# Use this tag to change the font size of LaTeX formulas included as images in +# the HTML documentation. When you change the font size after a successful +# doxygen run you need to manually remove any form_*.png images from the HTML +# output directory to force them to be regenerated. +# Minimum value: 8, maximum value: 50, default value: 10. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FORMULA_FONTSIZE = 10 + +# Use the FORMULA_TRANSPARENT tag to determine whether or not the images +# generated for formulas are transparent PNGs. Transparent PNGs are not +# supported properly for IE 6.0, but are supported on all modern browsers. +# +# Note that when changing this option you need to delete any form_*.png files in +# the HTML output directory before the changes have effect. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FORMULA_TRANSPARENT = YES + +# The FORMULA_MACROFILE can contain LaTeX \newcommand and \renewcommand commands +# to create new LaTeX commands to be used in formulas as building blocks. See +# the section "Including formulas" for details. + +FORMULA_MACROFILE = + +# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see +# https://www.mathjax.org) which uses client side JavaScript for the rendering +# instead of using pre-rendered bitmaps. Use this if you do not have LaTeX +# installed or if you want to formulas look prettier in the HTML output. When +# enabled you may also need to install MathJax separately and configure the path +# to it using the MATHJAX_RELPATH option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +USE_MATHJAX = NO + +# When MathJax is enabled you can set the default output format to be used for +# the MathJax output. See the MathJax site (see: +# http://docs.mathjax.org/en/v2.7-latest/output.html) for more details. +# Possible values are: HTML-CSS (which is slower, but has the best +# compatibility), NativeMML (i.e. MathML) and SVG. +# The default value is: HTML-CSS. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_FORMAT = HTML-CSS + +# When MathJax is enabled you need to specify the location relative to the HTML +# output directory using the MATHJAX_RELPATH option. The destination directory +# should contain the MathJax.js script. For instance, if the mathjax directory +# is located at the same level as the HTML output directory, then +# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax +# Content Delivery Network so you can quickly see the result without installing +# MathJax. However, it is strongly recommended to install a local copy of +# MathJax from https://www.mathjax.org before deployment. +# The default value is: https://cdn.jsdelivr.net/npm/mathjax@2. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_RELPATH = https://cdn.jsdelivr.net/npm/mathjax@2 + +# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax +# extension names that should be enabled during MathJax rendering. For example +# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_EXTENSIONS = + +# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces +# of code that will be used on startup of the MathJax code. See the MathJax site +# (see: +# http://docs.mathjax.org/en/v2.7-latest/output.html) for more details. For an +# example see the documentation. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_CODEFILE = + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box for +# the HTML output. The underlying search engine uses javascript and DHTML and +# should work on any modern browser. Note that when using HTML help +# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) +# there is already a search function so this one should typically be disabled. +# For large projects the javascript based search engine can be slow, then +# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to +# search using the keyboard; to jump to the search box use + S +# (what the is depends on the OS and browser, but it is typically +# , /