diff --git a/CMakeLists.txt b/CMakeLists.txt index fb0fadddfc19ebd151d2821bbcbd2962ffa23fc3..1a8a2aabb9c4315ca427dfa59956d793d06014a2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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 diff --git a/include/timeout.h b/include/iri_ros_tools/timeout.h similarity index 87% rename from include/timeout.h rename to include/iri_ros_tools/timeout.h index dec93a6f37da68faed462bebcd87383a763164b8..e45688e1b097868cc22dfac328af01d62f2da471 100644 --- a/include/timeout.h +++ b/include/iri_ros_tools/timeout.h @@ -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(); diff --git a/include/watchdog.h b/include/iri_ros_tools/watchdog.h similarity index 85% rename from include/watchdog.h rename to include/iri_ros_tools/watchdog.h index 731d5eba3f1036c13493434c5475b078230cf894..f9109976ac97267a3a7938bc00ead270a72a401f 100644 --- a/include/watchdog.h +++ b/include/iri_ros_tools/watchdog.h @@ -1,5 +1,5 @@ #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(); }; diff --git a/src/timeout.cpp b/src/timeout.cpp index c5565cf9f44d3f969760785a15bada9ea9a76742..600c9103e6c5156625ed64bb1c6350656676604e 100644 --- a/src/timeout.cpp +++ b/src/timeout.cpp @@ -1,4 +1,4 @@ -#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; diff --git a/src/watchdog.cpp b/src/watchdog.cpp index a1ab239b56496b8b63109d4ce5b733c9959d6547..11507a0eb8adeb49d1537eea24a6c7238ef75e50 100644 --- a/src/watchdog.cpp +++ b/src/watchdog.cpp @@ -1,4 +1,4 @@ -#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_);