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

Moved the header files to the iri_ros_tools folder inside the include folder.

Removed the update function from the watchdog class.
parent 285c2ce4
No related branches found
No related tags found
No related merge requests found
......@@ -77,9 +77,8 @@ find_package(catkin REQUIRED)
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
# LIBRARIES ${PROJECT_NAME}
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS roscpp
# DEPENDS system_lib
)
###########
......@@ -104,9 +103,6 @@ add_library(${PROJECT_NAME} src/timeout.cpp src/watchdog.cpp)
# add_dependencies(iri_ros_tool_node iri_ros_tool_generate_messages_cpp)
## Specify libraries to link a library or executable target against
# target_link_libraries(iri_ros_tool_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
......@@ -130,7 +126,7 @@ add_library(${PROJECT_NAME} src/timeout.cpp src/watchdog.cpp)
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# install(DIRECTORY include
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
......
......@@ -13,7 +13,7 @@ class CROSTimeout
pthread_mutex_t access_;
public:
CROSTimeout();
void start(ros::Duration &time);
void start(const ros::Duration &time);
void stop(void);
bool timed_out(void);
~CROSTimeout();
......
#ifndef _WATCHDOG_H
#define _WATCHDOF_H
#define _WATCHDOG_H
#include <ros/ros.h>
......@@ -11,7 +11,6 @@ class CROSWatchdog
public:
CROSWatchdog();
void reset(ros::Duration time);
void update(void);
bool is_active(void);
~CROSWatchdog();
};
......
#include "timeout.h"
#include "iri_ros_tools/timeout.h"
CROSTimeout::CROSTimeout()
{
......@@ -9,7 +9,7 @@ CROSTimeout::CROSTimeout()
this->active=false;
}
void CROSTimeout::start(ros::Duration &time)
void CROSTimeout::start(const ros::Duration &time)
{
pthread_mutex_lock(&this->access_);
this->time_period = time;
......
#include "watchdog.h"
#include "iri_ros_tools/watchdog.h"
CROSWatchdog::CROSWatchdog()
{
......@@ -13,7 +13,7 @@ void CROSWatchdog::reset(ros::Duration time)
pthread_mutex_unlock(&this->access_);
}
void CROSWatchdog::update(void)
bool CROSWatchdog::is_active(void)
{
static ros::Time start_time=ros::Time::now();
ros::Time current_time=ros::Time::now();
......@@ -21,12 +21,6 @@ void CROSWatchdog::update(void)
pthread_mutex_lock(&this->access_);
this->max_time-=(current_time-start_time);
start_time=current_time;
pthread_mutex_unlock(&this->access_);
}
bool CROSWatchdog::is_active(void)
{
pthread_mutex_lock(&this->access_);
if(this->max_time.toSec()<=0.0)
{
pthread_mutex_unlock(&this->access_);
......
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