Skip to content
Snippets Groups Projects
Commit ffac214a authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Added a bool to enable/disable the watchdog feature.

Added functions to enable and disable the watchdog.
Modified the function to set the watchdog period. It is now enable_watchdog(time).
parent 960d75a5
No related branches found
No related tags found
No related merge requests found
......@@ -116,7 +116,7 @@ class CModuleAction
* \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 amount of time the action is active or not. Its value is controlled by
* the enable_timeout() and disable_timeout() functions.
*
* To check whether the timeout is active or not, use the is_timeout_enabled()
......@@ -139,6 +139,17 @@ class CModuleAction
*/
CROSTimeout action_timeout;
// watchdog attributes
/**
* \brief Use the watchdog feature
*
* This attribute specifies whether the watchdog feature is to be used to limit
* the amount of time between action feedback messages. Its value is controlled by
* the enable_watchdog() and disable_watchdog() functions.
*
* To check whether the watchdog is active or not, use the is_watchdog_enabled()
* function.
*/
bool use_watchdog;
/**
* \brief Maximum time between feedback messages
*
......@@ -250,7 +261,8 @@ class CModuleAction
ROS_DEBUG_STREAM("CModuleAction::action_feedback: Got Feedback from server " << this->name << "!");
this->action_access.enter();
this->action_feedback_msg=*feedback;
this->feedback_watchdog.reset(ros::Duration(this->watchdog_time));
if(this->use_watchdog)
this->feedback_watchdog.reset(ros::Duration(this->watchdog_time));
this->action_access.exit();
}
public:
......@@ -287,16 +299,34 @@ class CModuleAction
*/
unsigned int get_max_num_retries(void);
/**
* \brief Sets the feedback watchdog time
* \brief Enables the actiin feedback watchdog
*
* This functions sets the maximum allowed time between two consecutive
* feedback messages before reporting an error. By default this value is
* set to 2.
* This function enables the internal action feedback watchdog to limit
* the maximum time between feedback messages. By default this feature is
* enabled.
*
* \param time_s the desired maximum time between feedback messages before
* reporting and error.
*/
void enable_watchdog(double time_s);
/**
* \brief Disables the action feedback watchdog
*
* This function disables the internal action feedback watchdog to limit
* the maximum time between feedback messgaes. By default this feature is
* enabled.
*/
void disable_watchdog(void);
/**
* \brief Checks whether the feedback watchdog is enabled or not
*
* This functions checks whether the internal feedback watchdog for the current
* action is enabled or not.
*
* \param time_s the maximum allowed time in seconds between two consecutive
* feedback messages.
* \return A boolean indicating whether the watchdog is enabled (true) or not
* (false)
*/
void set_feedback_watchdog_time(double time_s);
bool is_watchdog_enabled(void);
/**
* \brief Gets the feedback watchdog time
*
......@@ -542,6 +572,7 @@ CModuleAction<action_ros>::CModuleAction(const std::string &name,const std::stri
this->timeout_value=0.0;
this->timeout_value=DEFAULT_ACTION_TIMEOUT;
// waychdog
this->use_watchdog=true;
this->watchdog_time=DEFAULT_WATCHDOG_TIME;
// internal action
this->action_client=NULL;
......@@ -571,19 +602,37 @@ unsigned int CModuleAction<action_ros>::get_max_num_retries(void)
}
template<class action_ros>
void CModuleAction<action_ros>::set_feedback_watchdog_time(double time_s)
void CModuleAction<action_ros>::enable_watchdog(double time_s)
{
this->action_access.enter();
if(time_s>0.0)
{
this->watchdog_time=time_s;
this->use_watchdog=true;
this->feedback_watchdog.reset(ros::Duration(this->watchdog_time));
}
else
{
this->action_access.exit();
throw CModuleException(_HERE_,"Invalid watchdog time value",this->name);
throw CModuleException(_HERE_,"Invalid watchdog value",this->name);
}
this->action_access.exit();
}
template<class action_ros>
void CModuleAction<action_ros>::disable_watchdog(void)
{
this->action_access.enter();
this->use_watchdog=false;
this->action_access.exit();
}
template<class action_ros>
bool CModuleAction<action_ros>::is_watchdog_enabled(void)
{
return this->use_watchdog;
}
template<class action_ros>
double CModuleAction<action_ros>::get_feedback_watchdog_time(void)
{
......@@ -596,7 +645,7 @@ bool CModuleAction<action_ros>::is_watchdog_active(void)
this->action_access.enter();
if(this->enabled)
{
if(this->feedback_watchdog.is_active())
if(this->use_watchdog && this->feedback_watchdog.is_active())
{
this->status=ACTION_FB_WATCHDOG;
this->action_access.exit();
......@@ -675,7 +724,7 @@ template<class action_ros>
bool CModuleAction<action_ros>::is_timeout_active(void)
{
this->action_access.enter();
if(this->action_timeout.timed_out())
if(this->use_timeout && this->action_timeout.timed_out())
{
this->status=ACTION_TIMEOUT;
this->action_access.exit();
......@@ -753,10 +802,8 @@ action_status CModuleAction<action_ros>::get_state(void)
{
if(this->status==ACTION_RUNNING)
{
if(this->use_timeout && this->is_timeout_active())
this->status=ACTION_TIMEOUT;
if(this->is_watchdog_active())
this->status=ACTION_FB_WATCHDOG;
this->is_timeout_active();
this->is_watchdog_active();
}
}
else
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment