From 820b26e12eac1f77c63b46ae6bf1cf360bc0c6e6 Mon Sep 17 00:00:00 2001 From: Joan Perez Ibarz <jperez@iri.upc.edu> Date: Fri, 4 Feb 2011 11:37:20 +0000 Subject: [PATCH] updating documentation from iri_core packages --- .../iri_base_algorithm/iri_base_algorithm.h | 243 ++++++++++-------- 1 file changed, 140 insertions(+), 103 deletions(-) diff --git a/include/iri_base_algorithm/iri_base_algorithm.h b/include/iri_base_algorithm/iri_base_algorithm.h index e53d146..12727aa 100644 --- a/include/iri_base_algorithm/iri_base_algorithm.h +++ b/include/iri_base_algorithm/iri_base_algorithm.h @@ -18,11 +18,6 @@ // diagnostic updater include #include <diagnostic_updater/diagnostic_updater.h> -//check me out -#define INTERNAL_SPIN -#define DYNAMIC_CFG -#define DIAGNOSTICS - namespace algorithm_base { @@ -50,39 +45,24 @@ class AbstractAlgorithmNode * * This class provides a common framework for all kind of algorithms, similar to * the one defined for the ROS driver_base::DriverNode<TemplateDriver> for the - * driver environment. In this case, the template Algorithm class must - * In addition, a mainThread is provided like in the IriDriver - */ - -/** - * \brief IRI ROS Base Node Class + * driver environment. In this case, the template Algorithm class must be an + * implementation derivated from a common interface (preferably ROS defined). + * The inherit template design form allows complete access to the generic + * algorithm object while manteining flexibility to instantiate any object which + * inherits from it. * - * This class inherits from the ROS class driver_base::DriverNode<TemplateDriver> - * to provide an execution thread to the driver object. The TemplateDriver object - * must be an implementation of the CIriDriver class. The inherit template design - * form allows complete access to the driver object while manteining flexibility - * to instantiate any object inherit from CIriDriver. - * - * A shared library is generated together with CIriDriver class to force - * implementation of virtual methods to final user. Functions from ROS driver - * base class to perform tests, add diagnostics or hooks, are mainteined to - * implement common purpose behaviours and forwarded to the final user node class - * for specification. + * An abstract class is generated as a ROS package to force implementation of + * virtual methods in the generic algorithm layer. Functions to perform tests, + * add diagnostics or dynamically reconfigure the algorithm parameters are + * offered respecting the ROS driver_base terminology. Similarly to the + * IriBaseNodeDriver common purpose behaviours for all algorithm kinds can be + * defined and forwarded to each of the generic algorithm classes for specific + * operations. * + * In addition, a mainThread is provided like in the IriBaseNodeDriver class. * Threads are implemented using iri_utils software utilities. The mainThread() * function loops in a defined loop_rate_. In each iteration, the abstract * mainNodeThread() function defined in the inherit node class is called. - * - * Similarly, functions such as addDiagnostics() or addRunningTests() are prepared - * for detailing common features for all driver nodes while executing specific - * commands for each specification by calling the respective functions - * addNodeDiagnostics() and addNodeRunningTests() from the inherit node - * implementation. - * - * Instances of both CIriDriver and IriBaseNodeDriver can be easly generated with the - * iri_ros_scripts package. Similarly, data can be sent and read through ROS - * topics by using those scripts. The scripts can be downloaded from the - * iri_stack SVN. */ template <class Algorithm> class IriBaseAlgorithm : public AbstractAlgorithmNode @@ -127,13 +107,13 @@ class IriBaseAlgorithm : public AbstractAlgorithmNode Algorithm alg_; /** - * \brief node handle communication object + * \brief public node handle communication object * * This node handle is going to be used to create topics and services within * the node namespace. Additional node handles can be instantatied if * additional namespaces are needed. */ - ros::NodeHandle node_handle_; + ros::NodeHandle public_node_handle_; /** * \brief private node handle object @@ -171,22 +151,77 @@ class IriBaseAlgorithm : public AbstractAlgorithmNode diagnostic_updater::Updater diagnostic_; public: - IriBaseAlgorithm(); - ~IriBaseAlgorithm(); + /** + * \brief constructor + * + * This constructor initializes all the node handle objects, the main thread + * loop_rate_ and the diagnostic updater. It also instantiates the main + * thread of the class and the dynamic reconfigure callback. + */ + IriBaseAlgorithm(void); + + /** + * \brief destructor + * + * This destructor kills the main thread. + */ + ~IriBaseAlgorithm(void); - int spin(void); + /** + * \brief spin + * + * This method is meant to spin the node to update all ROS features. It also + * launches de main thread. Once the object is instantiated, it will not + * start iterating until this method is called. + */ + int spin(void); private: - //check me out - boost::shared_ptr<boost::thread> ros_thread_; + /** + * \brief ros spin thread + * + * This boost thread object will manage the ros::spin function. It is + * instantiated and launched in the spin class method. + */ + boost::shared_ptr<boost::thread> ros_thread_; + /** + * \brief dynamic reconfigure server + * + * The dynamic reconfigure server is in charge to retrieve the parameters + * defined in the config cfg file through the reconfigureCallback. + */ dynamic_reconfigure::Server<Config> dsrv_; -// dynamic_reconfigure::Server<Config>::CallbackType cb; protected: + /** + * \brief dynamic reconfigure server callback + * + * This method is called whenever a new configuration is received through + * the dynamic reconfigure. + * + * \param config an object with new configuration from all algorithm + * parameters defined in the config file. + * \param level integer referring the level in which the configuration + * has been changed. + */ void reconfigureCallback(Config &config, uint32_t level); + + /** + * \brief add diagnostics + * + * In this function ROS diagnostics applied to all algorithms nodes may be + * added. It calls the addNodeDiagnostics method. + */ void addDiagnostics(void); - virtual void addNodeDiagnostics(void) = 0; + + /** + * \brief node add diagnostics + * + * In this abstract function additional ROS diagnostics applied to the + * specific algorithms may be added. + */ + virtual void addNodeDiagnostics(void) = 0; // void addOpenedTests(void); // void addStoppedTests(void); @@ -194,34 +229,52 @@ class IriBaseAlgorithm : public AbstractAlgorithmNode // virtual void addNodeOpenedTests(void) = 0; // virtual void addNodeStoppedTests(void) = 0; // virtual void addNodeRunningTests(void) = 0; + + /** + * \brief main node thread + * + * This is the main thread node function. Code written here will be executed + * in every inherit algorithm node object. The loop won't exit until the node + * finish its execution. The commands implemented in the abstract function + * mainNodeThread() will be executed in every iteration. + * + * Loop frequency can be tuned my modifying loop_rate_ attribute. + * + * \param param is a pointer to a IriBaseAlgorithm object class. It is used + * to access to the object attributes and methods. + */ static void *mainThread(void *param); + + /** + * \brief specific node thread + * + * In this abstract function specific commands for each algorithm node + * have to be detailed. + */ virtual void mainNodeThread(void) = 0; }; -//check me out + template <class Algorithm> IriBaseAlgorithm<Algorithm>::IriBaseAlgorithm() : private_node_handle_("~"), + public_node_handle_(ros::this_node::getName()), dsrv_(private_node_handle_), diagnostic_(), loop_rate_(DEFAULT_RATE) { - // create the status thread - this->thread_server_=CThreadServer::instance(); - this->main_thread_id_="main_thread"; + // create thread server instance + this->thread_server_ = CThreadServer::instance(); + + // identify main thread + this->main_thread_id_ = "main_thread"; - //check me out + // create main thread and attach to server this->thread_server_->create_thread(this->main_thread_id_); this->thread_server_->attach_thread(this->main_thread_id_, this->mainThread, this); -#ifndef INTERNAL_SPIN - this->thread_server_->start_thread( this->main_thread_id_); -#endif - //check me out -// dynamic_reconfigure::Server<Config>::CallbackType cb; - // = boost::bind(&IriBaseAlgorithm<Algorithm>::reconfigureCallback, this, _1, _2); + // assign callback to dynamic reconfigure server dsrv_.setCallback(boost::bind(&IriBaseAlgorithm<Algorithm>::reconfigureCallback, this, _1, _2)); - } template <class Algorithm> @@ -231,111 +284,95 @@ IriBaseAlgorithm<Algorithm>::~IriBaseAlgorithm() this->thread_server_->kill_thread(this->main_thread_id_); } -#ifdef DYNAMIC_CFG template <class Algorithm> void IriBaseAlgorithm<Algorithm>::reconfigureCallback(Config &config, uint32_t level) { - //check me out this->alg_.config_ = config; } -#endif -#ifdef DIAGNOSTICS template <class Algorithm> void IriBaseAlgorithm<Algorithm>::addDiagnostics(void) { addNodeDiagnostics(); } -#endif template <class Algorithm> void *IriBaseAlgorithm<Algorithm>::mainThread(void *param) { + // retrieve base algorithm class IriBaseAlgorithm *iriNode = (IriBaseAlgorithm *)param; - //check me out -#ifndef INTERNAL_SPIN - - #ifdef DIAGNOSTICS - //initialize diagnostics - iriNode->diagnostic_.setHardwareID("none"); - iriNode->addDiagnostics(); - #endif - -#endif - while(ros::ok() && !ctrl_c_hit_count_) { - //run node stuff - iriNode->mainNodeThread(); + // run node stuff + iriNode->mainNodeThread(); -#ifdef DIAGNOSTICS - #ifdef DIAGNOSTICS - iriNode->diagnostic_.update(); - #endif -#endif - - //sleep remainder time - iriNode->loop_rate_.sleep(); + // sleep remainder time + iriNode->loop_rate_.sleep(); } + // kill main thread pthread_exit(NULL); } -#ifdef INTERNAL_SPIN template <class Algorithm> int IriBaseAlgorithm<Algorithm>::spin(void) { - #ifdef DIAGNOSTICS - //initialize diagnostics + // initialize diagnostics this->diagnostic_.setHardwareID("none"); this->addDiagnostics(); - #endif - //launch ros spin + // launch ros spin in different thread this->ros_thread_.reset( new boost::thread(boost::bind(&ros::spin)) ); assert(ros_thread_); - //launch node thread + // launch node thread this->thread_server_->start_thread( this->main_thread_id_); while(ros::ok() && !ctrl_c_hit_count_) { - #ifdef DIAGNOSTICS - this->diagnostic_.update(); - #endif + // update diagnostics + this->diagnostic_.update(); } - //stop ros + // stop ros ros::shutdown(); - //kill ros thread + // kill ros spin thread this->ros_thread_.reset(); return 0; } -#endif +// definition of the static Ctrl+C counter int AbstractAlgorithmNode::ctrl_c_hit_count_ = 0; -// namespace algorithm_base -// { - +/** + * \brief base main + * + * This main is common for all the algorithm nodes. The AlgImplTempl class + * refers to an specific implementation of a generic algorithm. + * + * First, ros::init is called providing the node name. Ctrl+C control is + * activated for sercure and safe exit. Finally, an AlgImplTempl object is + * defined and launched to spin for endless loop execution. + * + * \param argc integer with number of input parameters + * \param argv array with all input strings + * \param node_name name of the node + */ template <class AlgImplTempl> -int main(int argc, char **argv, std::string name) +int main(int argc, char **argv, std::string node_name) { - ros::init(argc, argv, name); + // ROS initialization + ros::init(argc, argv, node_name); - //check me out + // allow Ctrl+C management signal(SIGHUP, &AbstractAlgorithmNode::hupCalled); - //check me out + // define and launch generic algorithm implementation object AlgImplTempl algImpl; -#ifdef INTERNAL_SPIN algImpl.spin(); -#else - ros::spin(); -#endif return 0; } -- GitLab