diff --git a/include/iri_ros_tools/module.h b/include/iri_ros_tools/module.h index 2e390d24b68a08ee4e5742c98d883b62f0ba2a05..55513f4ce838ecdc1b2299e9f1bb02f5af98dcbe 100644 --- a/include/iri_ros_tools/module.h +++ b/include/iri_ros_tools/module.h @@ -15,40 +15,241 @@ #define MODULE_DEFAULT_RATE 10 +/** + * \brief Base class for all state machine modules + * + * This class may be used as a base class for state machine modules. It + * implements the following features: + * * an abstract function (state_machine()) that is called at a configurable + * rate to implement the actual state machine in inherited classes. This + * function must be implemented in the inherited classes. This function + * is called with the internal mutex locked. + * * A dynamic reconfigure server. The callback function associated to this + * server is abstract and must be implemnted in the inherited class. This + * class is a template on the dynamic reconfigure data structure. + * * An internal node handle is used to define the module namespace with the + * parameters provided at construction time (name and namespace). + * + * Any inherited class must call (preferably in the constructor) the start + * operation function in order to properly set up the internal operation of + * the class. + */ template<class ModuleCfg> class CModule { protected: - /* internal node handle */ + /** + * \brief internal ROS node handle + * + * A ROS node handle that can be used by inherited classes to initialize + * ROS interfaces. This node handle is initialized at construction time + * as follows: + * + * /<node namespace>/<provided namespace>/<provided name> + * + */ ros::NodeHandle module_nh; private: + /** + * \brief name of the module + * + * Attribute with the name of the module, together with the full namespace. + * This name is used to report information, errors and warnings regarding + * the module. + */ std::string name; + /** + * \brief rate in Hz of the internal thread + * + * This is the actual rate at which the state_machine() function will be + * called. Use the set_rate() and get_rate() function to modify and + * retrieve its value. + */ ros::Rate module_rate; + /** + * \brief Internal mutex + * + * Mutex variables to ensure atomic access to internal attributes from the + * state machine and the ROS callback functions. It is internally handled + * and the lock() and unlock() functions must be used to access it. + */ CMutex module_access; /* reconfiguer attributes */ + /** + * \brief Dynamic reconfigure server + * + * A dynamic reconfigure server which depends on the dynamic reconfigure + * data structure this class is template of. This server has the + * reconfigure_callback() callback function associated to it. + */ dynamic_reconfigure::Server<ModuleCfg> dyn_reconf; /* thread attributes */ + /** + * \brief IRI thread server + * + * Pointer to the single instance of the thread server in the current + * process. It is used to handle the class thread. + */ CThreadServer *thread_server; + /** + * \brief Name of the internal thread + * + * Name of the thread used to execute the state machine of the module. + * It is used to identify it inside the thread server. + */ std::string module_thread_id; /* event attributes */ + /** + * \brief IRI event server + * + * Pointer to the single instance of the event server in the current + * process. It is used to handle the class events. + */ CEventServer *event_server; + /** + * \brief Name of the event to terminate the internal thread + * + * Name of the event used to signal the termniation of the internal + * thread. It is used to identify it inside the event server. The + * activation of this event is monitored by the thread periodically. + */ std::string finish_thread_event_id; protected: + /** + * \brief Main thread function + * + * This is the main function of the internal thread. The thread itself is + * configured at contruction time, but it is not started until the + * start_operation() functions is called. This function monitors the + * internal event to know when it has to stop, and calls the state_machine() + * function at the desired rate. + */ static void *module_thread(void *param); + /** + * \brief Function to implement the state machine + * + * This is an abstract function that must be implemented by any inherited class + * in order to be able to instantiate an object. This function must implement + * the desired state machine of the module without blocking at any time, to + * ensure a correct operation. + * + * This function is called with the internal mutex locked(), and it is called + * at the desired rate. + * + * \param void pointer pointing to the this pointer of the current object. + * + * \return this functions always return a NULL pointer. + */ virtual void state_machine(void)=0; + /** + * \brief Dynamic reconfigure callback + * + * This abstarct function must be implemented by any inherited class in order + * to be able to instantiate an object. This function is called whenever a + * new dynamic reconfigure service call is received and must configure the + * module with the provided data. + * + * \param config reference to the dynamic reconfigure data structure with + * all the configuration data for the class. + * \param level integer representing the execution level at which the + * function has been called. In this case it has no meaning + * and can be ignored. + */ virtual void reconfigure_callback(ModuleCfg &config, uint32_t level)=0; + /** + * \brief function to start the operation of the class + * + * This function must be called in the inherited class constructor in order + * to start the internal thread and also start the dynamic reconfigure + * server. + * + * TODO: this function should disapear + */ void start_operation(void); + /** + * \brief lock the mutex + * + * Function to lock the internal mutex of the class. Since the mutex is not + * public or protected, inherited classes must use this function to access + * it. + */ void lock(void); + /** + * \brief unlock the mutex + * + * Function to unlock the internal mutex of the class. Since the mutex is not + * public or protected, inherited classes must use this function to access + * it. + */ void unlock(void); public: + /** + * \brief Constructor + * + * Constructor of the base class. This function initializes and configures all + * the internal attributes, but the object is not operating properly until the + * start_operation() funciton is called. + * + * \param name string with the desired name for the module. + * + * \param namespace string with the base namespace for the module. + */ CModule(const std::string &name); + /** + * \brief Function to set the rate + * + * This function sets the desired rate of the internal thread which defines + * the frequency at which the state_machine() function is called. + * + * If the desired rate is not valid, a CModuleException is thrown. + * + * \param rate_hz the desired rate of the internal thread in Hertz. It must be + * any non-negative float value. + */ void set_rate(double rate_hz); + /** + * \brief Function to get the rate + * + * This function returns the current value of the thread rate. By default this + * value is set to 10 Hz. + * + * \return the value of the current thread rate in hertz. + */ double get_rate(void); + /** + * \brief Function to get the name of the module + * + * This function returns the full name of the module, with the whole namespace. + * + * \return the name of the module. + */ std::string get_name(void); + /** + * \brief + * + */ bool set_parameter(ros::ServiceClient &service,const std::string &name,bool value); + /** + * \brief + * + */ bool set_parameter(ros::ServiceClient &service,const std::string &name,int value); + /** + * \brief + * + */ bool set_parameter(ros::ServiceClient &service,const std::string &name,std::string &value); + /** + * \brief + * + */ bool set_parameter(ros::ServiceClient &service,const std::string &name,double value); + /** + * \brief Destructor + * + * This function signals the internal thread to stop, waits until it finishes and + * the frees all the internal resources. + */ virtual ~CModule(); }; diff --git a/include/iri_ros_tools/module_action.h b/include/iri_ros_tools/module_action.h index a827d66d86a2d5c34b943205c3edce15018dc8bd..c282d2125dfac52d9ddb799a5f67edbdddab28d5 100644 --- a/include/iri_ros_tools/module_action.h +++ b/include/iri_ros_tools/module_action.h @@ -17,32 +17,186 @@ #define DEFAULT_ACTION_TIMEOUT 10 #define DEFAULT_WATCHDOG_TIME 2 -typedef enum {ACTION_IDLE,ACTION_RUNNING,ACTION_SUCCESS,ACTION_TIMEOUT,ACTION_FB_WATCHDOG,ACTION_ABORTED,ACTION_PREEMPTED} action_status; +/** + * \brief Possible action states returned by the get_state() function + * + * These are the possible states of the action associated to this class. Most + * of them represent actual states of the goal inside the action server, except + * for two: + * * ACTION_TIMEOUT: indicates the action did not finish in the alloed time + * * ACTION_WATCHDOG: indicate the action has not received feedback for a long + * time + */ +typedef enum {ACTION_IDLE, + ACTION_RUNNING, + ACTION_SUCCESS, + ACTION_TIMEOUT, + ACTION_FB_WATCHDOG, + ACTION_ABORTED, + ACTION_PREEMPTED} action_status; +/** + * \brief Action client wrapper + * + * This class wraps a simple ROS action client in order to simplify its use. + * This class is a template of any ROS action and provides the common features + * to start, cancel and monitor the current state of the goal. In addition, it + * provides the following features: + * + * * the maximum number of times the action can fail to start before reporting + * an error. + * * Timeout to control the maximum time the action can be active. + * * A watchdog to monitor the correct reception of the feedback of the action. + * + * All these new features can be configured using the class API. + * + * The action topics are created inside the namespace defined by the (optional) + * namespace and the actual name provided at contruction time as follows + * + * <main node namespace>/<class namespace>/<class name> + */ template<class action_ros> class CModuleAction { private: + /** + * \brief Internal Mutex + * + * This Mutex is used to ensure atomic access to the internal attributes + * of the class. + */ CMutex action_access; + /** + * \brief name of the action object + * + * Attribute with the name of the action object, together with the full + * namespace. This name is used to report information, errors and + * warnings regarding the action object. + */ std::string name; + /** + * \brief Status of the action + * + * This attribute holds the current action of the object. This can be any + * value of the action_status data type. This status is updated internally + * and the get_state() function should be used to access it. + */ action_status status; // number of retries attributes + /** + * \brief Number of tries to start the action + * + * This attribute holds the number of attempts to start the action. It is + * only used internally to handle possible start failures. + */ unsigned int current_num_retries; + /** + * \brief maximum number of start attempts + * + * This attribute holds the maximum number of attempts to start the action. + * This value can be modified by the user with the set_max_num_retries() + * functions, and the actual value can be obtain with the get_max_num_retries() + * functions. + */ unsigned int max_num_retries; // ROS node handle + /** + * \brief internal ROS node handle + * + * A ROS node handle used to initialize the internal ROS action. This node + * handle is initialized at construction time as follows: + * + * /<node namespace>/<provided namespace>/<provided name> + * + */ ros::NodeHandle nh; // timeout attributes + /** + * \brief Use the timeout feature + * + * This attribute specifies whether the timeout feature is to be used to limit + * the amount of time the action is active or not. Its value is controlles by + * the enable_timeout() and disable_timeout() functions. + * + * To check whether the timeout is active or not, use the is_timeout_enabled() + * function. + */ bool use_timeout; + /** + * \brief Timeout value in seconds + * + * This is the actual maximum time allowed to finish the action before reporting + * and error. This value can be set when starting a timeout with the start_timeout() + * function or when updating the value with the update_timeout() function. + */ double timeout_value; + /** + * \brief Timeout object + * + * This is a timeout object actually used to handle the timeout feature of this + * class. See the documentation of this class for further details. + */ CROSTimeout action_timeout; // watchdog attributes + /** + * \brief Maximum time between feedback messages + * + * This attribute holds the maximum time in seconds allowed between two consecutive + * feedback messages. This value can be modified with the set_feedback_watchdog_time(). + * To get the current value use the get_feedback_watchdog_time() function. + */ double watchdog_time; + /** + * \brief Watchdog object + * + * This is the watchdog object actually used to handle the watchdog feature of this + * class. This feature is also anables. See the documentation of this class for + * further details. + */ CROSWatchdog feedback_watchdog; // action attributes + /** + * \brief ROS topic messages names + * + * This declaration defines all the ROS topis names of the provided action. + */ ACTION_DEFINITION(action_ros); + /** + * \brief Action client object + * + * This points to the ROS action client object. See the documentation on this + * class for further details. + */ actionlib::SimpleActionClient<action_ros> *action_client; + /** + * \brief Result message of the action + * + * This attribute holds the result message of the last executed action. Use + * the get_result() function to get it. This data structure is updated by + * the action_done() callback. + */ Result action_result_msg; + /** + * \brief Feedback message of the action + * + * This attribute holds the last feedback message received of the current + * action. Use the get_feedback() function to get it. This data structure + * is updated by the action_feedback() callback. + */ Feedback action_feedback_msg; + /** + * \brief Action done callback + * + * This callback is called whenever the current action finishes. It stores + * the user defined result data structure into the internal attribute and + * reports how the action ended, both using the rosout feature and the + * internal status attribute. + * + * \param state termination state of the current action. Defined by ROS. + * + * \param result action dependant result data structure received from the + * action server. + */ void action_done(const actionlib::SimpleClientGoalState& state,const ResultConstPtr& result) { this->action_access.enter(); @@ -58,13 +212,28 @@ class CModuleAction } else if(state==actionlib::SimpleClientGoalState::SUCCEEDED) { - ROS_DEBUG_STREAM("CModuleAction::action_done: goal on server " << this->name << " successfull"); + ROS_INFO_STREAM("CModuleAction::action_done: goal on server " << this->name << " successfull"); this->status=ACTION_SUCCESS; } this->action_result_msg=*result; this->action_access.exit(); } + /** + * \brief Action active callback + * + * This callback is called when the action becomes active, after it has been + * received by the server. + */ void action_active(void); + /** + * \brief Action feedback callback + * + * This callback is called whenever new feedback data is received from the + * action server. This function updated the internal feedback data structure. + * + * \param feedback action dependant feedback data structure received from the + * action server. + */ void action_feedback(const FeedbackConstPtr& feedback) { ROS_DEBUG_STREAM("CModuleAction::action_feedback: Got Feedback from server " << this->name << "!"); @@ -74,20 +243,157 @@ class CModuleAction this->action_access.exit(); } public: + /** + * \brief Constructor + * + * Constructor of the action class. This function initializes and configures all + * the internal attributes, including the action client. + * + * \param name string with the desired name for the action. + * + * \param namespace string with the base namespace for the action. + + */ CModuleAction(const std::string &name,const std::string &name_space=std::string("")); + /** + * \brief Sets the maximum number of attempts to start the action + * + * This function sets the maximum number of attempts allowed to start the + * action before giving up. By default this value is set to 5. + * + * \param max_retries non-negative integer with the maximum number of attempts + * to start the action + */ void set_max_num_retries(unsigned int max_retries); + /** + * \brief Gets the maximum number of attempts to start the action + * + * This function returns the maximum number of attempts allowed to start the + * action before giving up. By default this value is set to 5. + * + * \return non-negative integer with the maximum number of attempts to start + * the action + */ unsigned int get_max_num_retries(void); + /** + * \brief Sets the feedback watchdog time + * + * This functions sets the maximum allowed time between two consecutive + * feedback messages before reporting an error. By default this value is + * set to 2. + * + * \param time_s the maximum allowed time in seconds between two consecutive + * feedback messages. + */ void set_feedback_watchdog_time(double time_s); + /** + * \brief Gets the feedback watchdog time + * + * This functions returns the maximum allowed time between two consecutive + * feedback messages before reporting an error. By default this value is + * set to 2. + * + * \return the maximum allowed time in seconds between two consecutive + * feedback messages. + */ double get_feedback_watchdog_time(void); + /** + * \brief Checks the state of the watchdog + * + * This function checks whether the internal watchdog has been activated + * because the feedback callback functions has not been called for longer + * than the allowed time. + * + * \return A boolean indicating whether the watchdog is active (true) or + * not (false) + */ bool is_watchdog_active(void); + /** + * \brief Enables the action timeout + * + * This function enables the internal action timeout to limit the maximum + * time the action can be active without finishing properly. By default + * this feature is disabled. + */ void enable_timeout(void); + /** + * \brief Disables the action timeout + * + * This function disables the internal action timeout to limit the maximum + * time the action can be active without finishing properly. By default + * this feature is disabled. + */ void disable_timeout(void); + /** + * \brief + * + * TODO: do it automatically in the make_request function + */ void start_timeout(double time_s); + /** + * \brief Updates the current timeout value + * + * This function updates the current timeout value, if it is enabled. The + * time already elapsed since the start of the action is not taken into + * account when updating the value, so the provided time will be the new + * timeout time. + * + * \param time_s the new timeout time in seconds to wait for the termination + * of the current action. + */ void update_timeout(double time_s); + /** + * \brief Stops the timeout + * + * This functions stops the internal timeout, if it is enabled, so that no + * timeout error will be reported. + */ void stop_timeout(void); + /** + * \brief Checks whether the timeout is enabled or not + * + * This functions checks whether the internal timeout value for the current + * action is enabled or not. + * + * \return A boolean indicating whether the timeout is enabled (true) or not + * (false) + */ bool is_timeout_enabled(void); + /** + * \brief Checks whether the timeout is active or not + * + * This functions chekcs whether the maximum time allowed to complete the + *action has elapsed or not. + * + * \return A boolean indicating whether the timeout is active (true) or not + * (false) + */ bool is_timeout_active(void); + /** + * \brief Function to get the name of the module + * + * This function returns the full name of the module, with the whole namespace. + * + * \return the name of the module. + * + */ std::string get_name(void); + /** + * \brief start the action + * + * This function start the action with the provided goal information. This function + * first checks whether the action server is connected or not. In case it is not + * connected it will return reporting a pending condition util the maximum number of + * repetitions has been reached. In this case it will report an error. + * + * If the action server is connected, it sends all the goal information, resets the + * feeedback watchdog and enables the internal timeout in case it is enabled. + * + * \param msg action dependant goal data structure to be send to the action server. + * + * \return the status of the request. It can be any value of the act_srv_status + * data type. + */ act_srv_status make_request(Goal &msg) { if(this->action_client->isServerConnected()) @@ -120,17 +426,69 @@ class CModuleAction } } + /** + * \brief Cancels the current action + * + * This function cancels the current action. When this function is called, + * the action in the action server may still be active, so it is necessary + * to check the is_finished() function to actually know when the action + * has ended. + */ void cancel(void); + /** + * \brief Checks whether the action has finished or not + * + * This function checks whether the current action has ended or not. The + * action may end for several reasons, use the get_state() function to + * know the exact cause. + * + * \return A boolean indicating whether the current actions has finished + * (true) or not (false); + */ bool is_finished(void); + /** + * \brief Returns the current status of the action + * + * This functions returns the current status of the action. If no action + * is active, the value returned by this function is meaningless. + * + * \return the current state of the action. It can be any value of the + * actio_status data structure. + */ action_status get_state(void); + /** + * \brief Returns the action result + * + * This function returns the action dependant result data structure + * returned by the action server when the last goal has ended. If no + * goal has been started of the current goal is still active, the + * value returned by this function is meaningless. + * + * \return an action dependant result data structure of the last + * executed action. + */ Result get_result(void) { return this->action_result_msg; } + /** + * \brief Returns the action feedback + * + * This function returns the last received action dependant feedback + * data structure. If no action is active, the value resturned by + * this functions is meaningless. + * + * \return the last action dependant feedback data structure received + * from the current goal. + */ Feedback get_feedback(void) { return this->action_feedback_msg; } + /** + * \brief Destructor + * + */ ~CModuleAction(); }; diff --git a/include/iri_ros_tools/module_dyn_reconf.h b/include/iri_ros_tools/module_dyn_reconf.h index d1a77425a168bdc3562e26e18b53af25bd555769..21f4aff7211ed3c32ceabf68de7948c9a40473f9 100644 --- a/include/iri_ros_tools/module_dyn_reconf.h +++ b/include/iri_ros_tools/module_dyn_reconf.h @@ -4,22 +4,156 @@ #include <dynamic_reconfigure/Reconfigure.h> #include <iri_ros_tools/module_service.h> +/** + * \brief Dynamic reconfigure client wrapper + * + * This class inherits from the generic CModuleService class to implement + * the specifics of the dynamic reconfigure service. It ptovides functions + * to set integer, boolean, float and string parameters of remote ROS nodes. + */ class CModuleDynReconf : protected CModuleService<dynamic_reconfigure::Reconfigure> { private: - std::string name; + /** + * \brief Name of the parameter to change + * + * This attribute stores the name of the parameter that is being changed + * when the service is called. It is then used by the check function to + * make sure the value has been changed successfully. + */ + std::string param_name; + /** + * \brief Boolean value to change + * + * This attribute stores the value of the parameter to be modified when + * the service is called. It is then used by the check function to make + * sure the value has been changed correctly. + */ bool bool_value; + /** + * \brief Integer value to change + * + * This attribute stores the value of the parameter to be modified when + * the service is called. It is then used by the check function to make + * sure the value has been changed correctly. + */ int int_value; + /** + * \brief String value to change + * + * This attribute stores the value of the parameter to be modified when + * the service is called. It is then used by the check function to make + * sure the value has been changed correctly. + */ std::string string_value; + /** + * \brief Double value to change + * + * This attribute stores the value of the parameter to be modified when + * the service is called. It is then used by the check function to make + * sure the value has been changed correctly. + */ double double_value; protected: + /** + * \brief Service data check callback + * + * This callback function is called when the service response is received + * to check whether the parameter has been changed successfully or not. + * + * \param msg Dynamic reconfigure message with the request and response + * data. + * + * \return A boolean indicating whether the parameter has been changed + * successfully (true) or not (false) + * + */ bool check_dyn_reconf(dynamic_reconfigure::Reconfigure &msg); public: + /** + * \brief Constructor + * + */ CModuleDynReconf(const std::string &name,const std::string &name_space=std::string("")); + /** + * \brief Sets a parameter of type boolean + * + * This functions sets a parameter of type boolean. It calls the dynamic + * reconfigure server with the provided data and waits for an answer. If + * the data has not been changed, this function will report an error, as + * well as if the service call itself fails or is pending. + * + * \param name String with the name of the parameter to change. This must + * coincide with a parameter name on the associated dynamic + * reconfigure server. + * + * \param value A boolean with the new value for the parameter. + * + * \return A boolean indicating whether the parameter has been successfully + * changed (true) or not (false) + */ bool set_parameter(const std::string &name,bool value); + /** + * \brief Sets a parameter of type integer + * + * This functions sets a parameter of type integer. It calls the dynamic + * reconfigure server with the provided data and waits for an answer. If + * the data has not been changed, this function will report an error, as + * well as if the service call itself fails or is pending. + * + * \param name String with the name of the parameter to change. This must + * coincide with a parameter name on the associated dynamic + * reconfigure server. + * + * \param value An integer with the new value for the parameter. This value + * must be inside the valid value range of the parameter. + * + * \return A boolean indicating whether the parameter has been successfully + * changed (true) or not (false) + */ bool set_parameter(const std::string &name,int value); + /** + * \brief Sets a parameter of type string + * + * This functions sets a parameter of type string. It calls the dynamic + * reconfigure server with the provided data and waits for an answer. If + * the data has not been changed, this function will report an error, as + * well as if the service call itself fails or is pending. + * + * \param name String with the name of the parameter to change. This must + * coincide with a parameter name on the associated dynamic + * reconfigure server. + * + * \param value A string with the new value for the parameter. This value + * must be inside the valid value range of the parameter. + * + * \return A boolean indicating whether the parameter has been successfully + * changed (true) or not (false) + */ bool set_parameter(const std::string &name,std::string &value); + /** + * \brief Sets a parameter of type double + * + * This functions sets a parameter of type double. It calls the dynamic + * reconfigure server with the provided data and waits for an answer. If + * the data has not been changed, this function will report an error, as + * well as if the service call itself fails or is pending. + * + * \param name String with the name of the parameter to change. This must + * coincide with a parameter name on the associated dynamic + * reconfigure server. + * + * \param value A double with the new value for the parameter. This value + * must be inside the valid value range of the parameter. + * + * \return A boolean indicating whether the parameter has been successfully + * changed (true) or not (false) + */ bool set_parameter(const std::string &name,double value); + /** + * \brief Destructor + * + */ ~CModuleDynReconf(); }; @@ -34,7 +168,7 @@ bool CModuleDynReconf::check_dyn_reconf(dynamic_reconfigure::Reconfigure &msg) for(i=0;i<msg.response.config.bools.size();i++) { - if(msg.response.config.bools[i].name==this->name) + if(msg.response.config.bools[i].name==this->param_name) { if(msg.response.config.bools[i].value!=this->bool_value) { @@ -44,7 +178,7 @@ bool CModuleDynReconf::check_dyn_reconf(dynamic_reconfigure::Reconfigure &msg) } for(i=0;i<msg.response.config.ints.size();i++) { - if(msg.response.config.ints[i].name==this->name) + if(msg.response.config.ints[i].name==this->param_name) { if(msg.response.config.ints[i].value!=this->int_value) { @@ -54,7 +188,7 @@ bool CModuleDynReconf::check_dyn_reconf(dynamic_reconfigure::Reconfigure &msg) } for(i=0;i<msg.response.config.strs.size();i++) { - if(msg.response.config.strs[i].name==this->name) + if(msg.response.config.strs[i].name==this->param_name) { if(msg.response.config.strs[i].value!=this->string_value) { @@ -64,7 +198,7 @@ bool CModuleDynReconf::check_dyn_reconf(dynamic_reconfigure::Reconfigure &msg) } for(i=0;i<msg.response.config.doubles.size();i++) { - if(msg.response.config.doubles[i].name==this->name) + if(msg.response.config.doubles[i].name==this->param_name) { if(msg.response.config.doubles[i].value!=this->double_value) { @@ -86,7 +220,7 @@ bool CModuleDynReconf::set_parameter(const std::string &name,bool value) set_params_srv.request.config.bools.resize(1); set_params_srv.request.config.bools[0].name=name; set_params_srv.request.config.bools[0].value=value; - this->name=name; + this->param_name=name; this->bool_value=value; switch(this->call(set_params_srv)) { @@ -110,7 +244,7 @@ bool CModuleDynReconf::set_parameter(const std::string &name,int value) set_params_srv.request.config.ints.resize(1); set_params_srv.request.config.ints[0].name=name; set_params_srv.request.config.ints[0].value=value; - this->name=name; + this->param_name=name; this->int_value=value; switch(this->call(set_params_srv)) { @@ -134,7 +268,7 @@ bool CModuleDynReconf::set_parameter(const std::string &name,std::string &value) set_params_srv.request.config.strs.resize(1); set_params_srv.request.config.strs[0].name=name; set_params_srv.request.config.strs[0].value=value; - this->name=name; + this->param_name=name; this->string_value=value; switch(this->call(set_params_srv)) { @@ -158,7 +292,7 @@ bool CModuleDynReconf::set_parameter(const std::string &name,double value) set_params_srv.request.config.doubles.resize(1); set_params_srv.request.config.doubles[0].name=name; set_params_srv.request.config.doubles[0].value=value; - this->name=name; + this->param_name=name; this->double_value=value; switch(this->call(set_params_srv)) { diff --git a/include/iri_ros_tools/module_service.h b/include/iri_ros_tools/module_service.h index ec1d43ad3eb2bbc35f6f6d1caa692054abe4ea1b..776ccfcb9a69e4027c976f21a6dffc1013326976 100644 --- a/include/iri_ros_tools/module_service.h +++ b/include/iri_ros_tools/module_service.h @@ -6,25 +6,165 @@ #define DEFAULT_SERVICE_MAX_RETRIES 5 +/** + * \brief Service client wrapper + * + * This class wraps a simple ROS service client in order to simplify its use. + * This class is a template of any ROS service and provides the common features + * to call the service and, in addition, it also provides the following features: + * + * * the maximum number of times the action can fail to start before reporting + * an error. + * + * All these new features can be configured using the class API. + * + * The service name is created inside the namespace defined by the (optional) + * namespace and the actual name provided at contruction time as follows + * + * <main node namespace>/<class namespace>/<class name> + + */ template<class service_msg> class CModuleService { private: + /** + * \brief name of the service object + * + * Attribute with the name of the service object, together with the full + * namespace. This name is used to report information, errors and + * warnings regarding the service object. + * + */ std::string name; + /** + * \brief Number of tries to start the action + * + * This attribute holds the number of attempts to call the service. It is + * only used internally to handle possible start failures. + * + */ unsigned int current_num_retries; + /** + * \brief maximum number of start attempts + * + * This attribute holds the maximum number of attempts to call the service. + * This value can be modified by the user with the set_max_num_retries() + * functions, and the actual value can be obtain with the get_max_num_retries() + * functions. + * + */ unsigned int max_num_retries; + /** + * \brief internal ROS node handle + * + * A ROS node handle used to initialize the internal ROS service. This node + * handle is initialized at construction time as follows: + * + * /<node namespace>/<provided namespace>/<provided name> + * + */ ros::NodeHandle nh; + /** + * \brief ROS service client + * + * This attribute is the ROS service client object. See the documentation on this + * class for further details. + */ ros::ServiceClient service_client; + /** + * \brief Call completion callback + * + * Pointer to a function to check whether the information returned by the service + * call is valid or not. If this function pointer is not initialized, no check is + * performed. By default this function points to the default_call_check() function. + */ boost::function< bool(service_msg &msg) > call_successfull; protected: + /** + * \brief Default completion callback + * + * This is the default callback function used to check the data returned by the + * service call. It always returns true since no check is performed. + * + * \param msg The complete service dependant message, with both the request and + * the response. + * + * \return A boolean indicating whether the data received is valid or not. + */ bool default_call_check(service_msg &msg); public: + /** + * \brief Constructor + * + * Constructor of the service class. This function initializes and configures all + * the internal attributes, including the service client. + * + * \param name string with the desired name for the service. + * + * \param namespace string with the base namespace for the service. + */ CModuleService(const std::string &name,const std::string &name_space=std::string("")); + /** + * \brief Sets the maximum number of attempts to start the action + * + * This function sets the maximum number of attempts allowed to start the + * action before giving up. By default this value is set to 5. + * + * \param max_retries non-negative integer with the maximum number of attempts + * to start the action + * + */ void set_max_num_retries(unsigned int max_retries); + /** + * \brief Gets the maximum number of attempts to start the action + * + * This function returns the maximum number of attempts allowed to start the + * action before giving up. By default this value is set to 5. + * + * \return non-negative integer with the maximum number of attempts to start + * the action + * + */ unsigned int get_max_num_retries(void); + /** + * \brief Function to get the name of the module + * + * This function returns the full name of the module, with the whole namespace. + * + * \return the name of the module. + * + */ std::string get_name(void); + /** + * \brief Sets the callback function + * + * This function sets the user function to check the data returned by the service + * call. By default a dummy check function is used which always returns true. + * + * \param function pointer to a function which accepts a service dependant data + * structure and returns a boolean: + * bool <name>(service_msg &msg) + */ void set_call_check_function(const boost::function< bool(service_msg &msg) > &function); + /** + * \brief Calls the service + * + * This function actually calls the service with the provided information. If + * the call is unsuccessfull or the data check reports an error, this functions + * reports the call is pending, until the maximum number of retries has been + * done. + * + * \param msg service dependant goal data structure to be send to the service server. + * + * \return the status of the request. It can be any value of the act_srv_status + * data type. + */ act_srv_status call(service_msg &msg); + /** + * \brief Destructor + * + */ ~CModuleService(); }; diff --git a/include/iri_ros_tools/timeout.h b/include/iri_ros_tools/timeout.h index e45688e1b097868cc22dfac328af01d62f2da471..6b1221345a470390a7cacd81ae8477d241411009 100644 --- a/include/iri_ros_tools/timeout.h +++ b/include/iri_ros_tools/timeout.h @@ -3,19 +3,86 @@ #include <ros/ros.h> +/** + * \brief Class to handle timeouts in ROS + * + * This class is intended to handle timeouts using ROS infrastructure. This + * class works by polling instead of being event driver to simplify its use. + * When started with the start() function, the current time and the desired + * lapse time are stored internally. Then, only when the timed_out() function + * is called, the actual violation of the desired timeout is checked. + */ class CROSTimeout { private: + /** + * \brief Timeout active + * + * This attribute indicates whether the timeout object has been started + * or not. This attribute is internally handled. + */ bool active; + /** + * \brief Initial time + * + * This is the time from which the timeout is calculated. It is initialized + * when the start() function is called. + */ ros::Time start_time; + /** + * \brief Duration of the timeout + * + * This is the desired timeout value. It is initialized when the start() + * function is called. This value is added to the start time to compute + * whether the timeout is active or not. + */ ros::Duration time_period; // mutex + /** + * \brief Internal Mutex + * + * This Mutex is used to ensure atomic access to the internal attributes + * of the class. + */ pthread_mutex_t access_; public: + /** + * \brief Constructor + * + */ CROSTimeout(); + /** + * \brief Starts the timeout operation + * + * This functions starts and enables the operation of the timeout. It takes + * the current time and the desired period and stores them internally. + * + * \param time a ROS Duration object with teh desired timeout value in + * seconds. + */ void start(const ros::Duration &time); + /** + * \brief Stops the current timeout + * + * This functions stops any active timeout so that the timed_out() function + * will never return true. If there is no active timeout, this function + * does nothing. + */ void stop(void); + /** + * \brief Checks the state of the current timeout + * + * This function checks whether the desired timeout time has elapsed or not. + * If no timeout is active, this function always returns false. + * + * \return a boolean indicating whether the desired time has elapsed (true) + * or not (false) + */ bool timed_out(void); + /** + * \brief Destructor + * + */ ~CROSTimeout(); }; diff --git a/include/iri_ros_tools/watchdog.h b/include/iri_ros_tools/watchdog.h index 1e82c43b96eeb1077e66cf6582e66c279b507c16..3e57acfcfd3e086a72c0692d7271525b57b64d4d 100644 --- a/include/iri_ros_tools/watchdog.h +++ b/include/iri_ros_tools/watchdog.h @@ -3,16 +3,73 @@ #include <ros/ros.h> +/** + * \brief Class to handle watchdogs in ROS + * + * This class is intented to handle watchdogs using ROS infrastructure. This + * class works by polling instead of being event driven to simplify its use. + * This class starts operating when an object is instantiated, and the reset() + * function must be called with the desired watchdog time to ensure it does + * not get active. + * + * Only when the is_active() function is called, the actual violation of the + * watchdog period is checked. + */ class CROSWatchdog { private: + /** + * \brief Initial time of the monitoring process + * + * This is the time at which the watchdog period started. It is initialized + * with the time at which the reset() function is called. + */ ros::Time start_time; + /** + * \brief Maximum period of the watchdog + * + * This period is the maximum time allowed to call the reset() function + * again before reporting an error. It is initialized when the reset + * function is called. + */ ros::Duration max_time; + /** + * \brief Internal Mutex + * + * This Mutex is used to ensure atomic access to the internal attributes + * of the class. + */ pthread_mutex_t access_; public: + /** + * \brief Constructor + * + */ CROSWatchdog(); + /** + * \brief Resets the watchdog object + * + * This function is used to reset the watchdog time. It should be called + * inside the callback function or inside the process to monitor. The + * maximum period can be modified whenever this function is called. + * + * \param time Maximum period, in seconds, allowed to call this function + *^ again before reporting and error. + * + */ void reset(const ros::Duration &time); + /** + * \brief Checks if the watchdog has not been reset for the allowed time + * + * This function checks whether the watchdog object has been reset in the + * allowed time or not. The actual violation of the watchdog period is + * performed only when this function is called. + */ bool is_active(void); + /** + * \brief Destructor + * + */ ~CROSWatchdog(); };