diff --git a/CMakeLists.txt b/CMakeLists.txt index 926896be739aa4dd14a226a1e37a3985819f43f6..157d8e74d232c1bb092945c9cbbb9357f475b89f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,13 +1,23 @@ cmake_minimum_required(VERSION 2.8.3) project(iri_base_driver) +# set(CMAKE_BUILD_TYPE "DEBUG") + +## Add support for C++11, supported in ROS Kinetic and newer +# add_definitions(-std=c++11) + ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages -find_package(catkin REQUIRED) +find_package(catkin REQUIRED COMPONENTS + roscpp + dynamic_reconfigure + message_generation +) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) +find_package(Boost REQUIRED COMPONENTS system thread) ## Uncomment this if the package has a setup.py. This macro ensures ## modules and global scripts declared therein get installed @@ -39,11 +49,10 @@ find_package(catkin REQUIRED) ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) ## Generate messages in the 'msg' folder -# add_message_files( -# FILES -# Message1.msg -# Message2.msg -# ) +add_message_files( + FILES + SensorLevels.msg +) ## Generate services in the 'srv' folder # add_service_files( @@ -60,10 +69,10 @@ find_package(catkin REQUIRED) # ) ## Generate added messages and services with any dependencies listed here -# generate_messages( -# DEPENDENCIES -# std_msgs # Or other packages containing msgs -# ) +generate_messages( + DEPENDENCIES + std_msgs # Or other packages containing msgs +) ################################### ## catkin specific configuration ## @@ -77,8 +86,8 @@ find_package(catkin REQUIRED) catkin_package( INCLUDE_DIRS include LIBRARIES ${PROJECT_NAME} - CATKIN_DEPENDS roscpp driver_base dynamic_reconfigure -# DEPENDS system_lib + CATKIN_DEPENDS roscpp dynamic_reconfigure message_runtime + DEPENDS Boost ) ########### @@ -88,13 +97,21 @@ catkin_package( ## Specify additional locations of header files ## Your package locations should be listed before other locations # include_directories(include) -INCLUDE_DIRECTORIES(include) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} +) ## Declare a cpp library # add_library(foo # src/${PROJECT_NAME}/foo.cpp # ) add_library(${PROJECT_NAME} src/iri_base_driver.cpp) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} +) ## Declare a cpp executable # add_executable(foo_node src/foo_node.cpp) @@ -102,6 +119,7 @@ add_library(${PROJECT_NAME} src/iri_base_driver.cpp) ## Add cmake target dependencies of the executable/library ## as an example, message headers may need to be generated before nodes # add_dependencies(foo_node foo_generate_messages_cpp) +add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS}) ## Specify libraries to link a library or executable target against # target_link_libraries(foo_node diff --git a/README.md b/README.md new file mode 100644 index 0000000000000000000000000000000000000000..e2b3517110f6ddce73acc1401918e30dd20a2fb0 --- /dev/null +++ b/README.md @@ -0,0 +1,118 @@ +# Description +This project is intended to be used as a base class for ROS nodes that have to communicate with external hardware. The next diagram shows the basic structure of the IRI ROS base driver node: + +<img src="doc/images/iri_base_driver_diagram.png" alt="Basic structure of the IRI ROS base driver node" width="998" height="630"> + +This node was originally based on the [ROS driver_base node](http://wiki.ros.org/driver_base) which is now deprecated. Since then, it re-implements most of the driver_base features. + +This node is structured into two parts, both implemented as C++ classes: + +## Driver +This part is intended for the implementation of the driver itself. The use of an external library to implement the driver is strongly recommended to separate the driver functionality from the ROS middleware. However it is also possible to implement the driver here. The main features of this part are listed next, and a detailed description can be found below. + +* State machine to control the open, close, start and stop action of the driver. +* Mutex + +<details><summary>Detailed features description</summary> +<p> + +### State machine +The next figure shows the possible states and transitions (actions) between them of the state machine implemented for the driver. + +<img src="doc/images/state_machine.png" alt="State diagram of the state machine implemented in the driver part" width="635" height="455"> + +The driver tries to transition form the initial state (CLOSED) to the RUNNING state every second until it succeeds. To do so, each transition calls a function that must be implemented by the inherited class (openDriver(), closeDriver(), startDriver() and stopDriver()). These functions should interact with the actual hardware to perform the desired action. If the hardware does not support one or more of these actions, the corresponding functions should do nothing but return success (true). + +Some of the parameters of the driver may not be changed on the RUNNING state. Therefore, each of the parameters defined in the dynamic reconfigure interface of the driver node (see below for more information) provides the driver state in which it should be modified. Whenever the value of one of these parameters is changed, the state machine automatically transitions to the desired state, and then returns to the previous one, once the parameter has been updated. + +In addition to the driver transition action functions, a set of callback functions are also provided so that the driver node can perform some action (if necessary) after the driver has been opened (postOpenHook) or started (postStartHook), and before it is stopped (preStopHook) or closed (preCloseHook). These functions do nothing by default, but may be implemented by the inherited class to perform any required action. + +### Mutex +The driver part provides a mutex to protect the access to critical information. This mutex can be used internally by the driver functions and also by the driver node through a set of public functions of the driver class (lock(), unlock() and try_enter()). Make sure the mutex is left unlocked after use to avoid blocking the normal operation of the node. + +</p> +</details> + +## Driver node +This part is intended for the implementation of the ROS interfaces (topics, services and actions) and other ROS tools. It has an object of the driver class to have access to have full access to the driver functionalities. The main features of this part are listed next, and a detailed description can be found below. + +* Independent thread with configurable rate. +* Dynamic reconfigure server. +* Diagnostics publisher. +* Public and private ROS node handlers. + +<details><summary>Detailed features description</summary> +<p> + +### Threads +The driver node provides three separate threads: + +* The spin thread is used to call the ROS spin() function. The single threaded version of this function is used, so that all callbacks are executed, sequentially, in the same thread. +* The user thread is used to provide the ability to execute code in parallel and avoid blocking the callback functions. This thread is handled internally when the class is created and destroyed and a single function is provided to the user (mainNodeThread) which is called at a desired rate. The thread rate can be handled with the *setRate()* and *getRate()* functions. The user thread function is only called when the driver is in the RUNNING state. +* The main thread is used to handle the state machine of the driver and publish the node diagnostics data. + +### Dynamic reconfigure +A dynamic reconfigure server is initialized by default. It has an associated .cfg file located in the *cfg* folder where the user can define all the parameters that can be updated at run-time. Whenever a parameter value is changed (using the [rqt_reconfigure](http://wiki.ros.org/rqt_reconfigure)) application) two callback functions are called: + +* reconfigure callback at the driver part (config_update). +* reconfigure callback at the driver node part (node_config_update) + +Each callback receives the whole dynamic reconfigure data structure, but should only use its associated parameters. + +All node parameters can be defined this way, but it is recommended to only use it for run-time dynamic parameters. + +### Diagnostic publisher +A diagnostic publisher is also initialized by default. It provides the ability to collect status data from the driver and the driver node, and publishes it. The [rqt_runtime_monitor](http://wiki.ros.org/rqt_runtime_monitor) application can be used to monitor the diagnostics. + +By default a single diagnostic is published with the current status of the driver (CLOSED, OPENED or RUNNING). Additional diagnostics can be added at star-up by the user with the addNodeDiagnostics() function which can be implemented in the inherited class. For further information on ROS diagnostics feature go [here](http://wiki.ros.org/diagnostics). + +### ROS node Handlers +The driver node provides two separate ROS NodeHandlers: + +* the public node handle is initialized by a node handle provided to the constructor of the driver node. If no node handle is defined, "/" will be used. +* the private node handle is initialized to "~" by default. + +These node handlers can be used to get/set ROS parameters and to set-up ROS interfaces. Depending on the node handle used, the namespace of the corresponding parameter or interface will be different. + +</p> +</details> + +# ROS Interface + +### Service servers +- *~/set_parameters* ([dynamic_reconfigure/Reconfigure.srv](http://docs.ros.org/melodic/api/dynamic_reconfigure/html/srv/Reconfigure.html)): + Service to dynamically change the parameters of the node. Only the parameters defined in the .cfg file can be modified this way. + +### topic publishers +- */diagnostics* ([diagnostic_msgs/DiagnosticArray](http://docs.ros.org/api/diagnostic_msgs/html/msg/DiagnosticArray.html)): + Topic with all the diagnostics published by the node. + +### Parameters +- **rate** *(double; Default: 10.0; Max: 1000.0; Min: 0.1)*: + The rate of execution of the user thread in Hz. + +# Dependencies +This base node has no dependencies. + +# How to use it + +This ROS node is not designed to be used on its own, an inherited class is always required. + +To simplify the process of inheriting from this class, there is an script (*create_driver_package*) which creates a ROS driver package using this node as a base class. + +Also, there exist other scripts to easily add ROS interfaces (topic publishers or subscribers, service servers or clients and action servers or clients) and also TF listener or broadcaster. + +Check the [IRI ROS scripts](https://gitlab.iri.upc.edu/labrobotica/ros/iri_core/iri_ros_scripts) page for further information on all these scripts. + +## Disclaimer + +Copyright (C) Institut de Robòtica i Informà tica Industrial, CSIC-UPC. +Mantainer IRI labrobotics (labrobotica@iri.upc.edu) + +This package is distributed in the hope that it will be useful, but without any warranty. It is provided "as is" without warranty of any kind, either expressed or implied, including, but not limited to, the implied warranties of merchantability and fitness for a particular purpose. The entire risk as to the quality and performance of the program is with you. should the program prove defective, the GMR group does not assume the cost of any necessary servicing, repair or correction. + +In no event unless required by applicable law the author will be liable to you for damages, including any general, special, incidental or consequential damages arising out of the use or inability to use the program (including but not limited to loss of data or data being rendered inaccurate or losses sustained by you or third parties or a failure of the program to operate with any other programs), even if the author has been advised of the possibility of such damages. + +You should have received a copy of the GNU Lesser General Public License +along with this program. If not, see <http://www.gnu.org/licenses/> + diff --git a/doc/images/iri_base_driver_diagram.png b/doc/images/iri_base_driver_diagram.png new file mode 100644 index 0000000000000000000000000000000000000000..dba20cbeac9e23c09b656bfc75f3247770dd0fbb Binary files /dev/null and b/doc/images/iri_base_driver_diagram.png differ diff --git a/doc/images/state_machine.png b/doc/images/state_machine.png new file mode 100644 index 0000000000000000000000000000000000000000..9863d9b8785cf63c4c1ecec2433d3b2ea174c1c1 Binary files /dev/null and b/doc/images/state_machine.png differ diff --git a/doc/iri_base_driver.odp b/doc/iri_base_driver.odp new file mode 100644 index 0000000000000000000000000000000000000000..1cc555d127cc145581d894b894b1be1ae32c6221 Binary files /dev/null and b/doc/iri_base_driver.odp differ diff --git a/doc/state_machine.odp b/doc/state_machine.odp new file mode 100644 index 0000000000000000000000000000000000000000..c7fa83f795c8d69dee9295859aea04fbeefd72bb Binary files /dev/null and b/doc/state_machine.odp differ diff --git a/include/iri_base_driver/iri_base_driver.h b/include/iri_base_driver/iri_base_driver.h index 90d5cac9a19a3240932fe71af64f580ee45f14d1..02bbc4b2a9642732f1ea1f016bf95d6a91696f4d 100644 --- a/include/iri_base_driver/iri_base_driver.h +++ b/include/iri_base_driver/iri_base_driver.h @@ -2,11 +2,11 @@ // Author Sergi Hernandez & Joan Perez // All rights reserved. // -// This file is part of iri-ros-pkg +// This file is part of iri-ros-pkg. // iri-ros-pkg is free software: you can redistribute it and/or modify // it under the terms of the GNU Lesser General Public License as published by // the Free Software Foundation, either version 3 of the License, or -// at your option) any later version. +// at your option any later version. // // This program is distributed in the hope that it will be useful, // but WITHOUT ANY WARRANTY; without even the implied warranty of @@ -20,12 +20,16 @@ #define _IRI_BASE_DRIVER_H // ros base driver class -#include "driver_base/driver.h" #include "ros/ros.h" +// boost libraries +#include <boost/function.hpp> + namespace iri_base_driver { +typedef enum {CLOSED=0,OPENED=1,RUNNING=2} state_t; + /** * \brief IRI ROS Base Driver Class * @@ -34,41 +38,56 @@ namespace iri_base_driver * framework to integrate functional drivers implemented in C++ with the ROS * driver structure. A shared library is generated together with IriBaseNodeDriver * class to force implementation of virtual methods to final user. Common use - * functions to open, close, start and stop a driver need to be filled up when - * instantiating this class. ROS provides state transition methods to change + * functions to open, close, start and stop a driver need to be filled up when + * instantiating this class. ROS provides state transition methods to change * from one state to another. * * This class is used as an intermediate level between ROS basic classes and the - * user final driver implementation. Methods to manage drivers are implemented + * user final driver implementation. Methods for managing drivers are implemented * to provide common features to all driver-type objects. New methods are * provided to the user for the specific driver needs. * * Instances of both IriBaseDriver and IriBaseNodeDriver can be easly generated - * with the iri_ros_scripts package. Similarly, data can be sent and read + * 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. + * from the GitLab repository (See http://wiki.iri.upc.edu). */ -class IriBaseDriver : public driver_base::Driver +class IriBaseDriver { - protected: - /** - * \brief driver unique identifier - * - * This value is used to identify each driver. Must be set before changing - * the driver_base::state=run. Use the abstract function setDriverId(). - */ - std::string driver_id_; + private: + state_t current_state_; /** - * \brief variable to handle the mutual exclusion mechanism + * \brief Variable to handle the mutual exclusion mechanism * - * this variable is automatically initialized when an object of this class + * This variable is automatically initialized when an object of this class * or any inherited class is created and holds all the necessary information * to handle any shared resource. * */ pthread_mutex_t access_; + pthread_mutex_t internal_access_; + + boost::function< void() > postOpenHook; + + boost::function< void() > preCloseHook; + + boost::function< void() > postStartHook; + + boost::function< void() > preStopHook; + + /** + * \brief driver unique identifier + * + * This value is used to identify each driver. Must be set before changing + * the driver_base::state=run. Use the abstract function setDriverId(). + */ + std::string driver_id_; + + std::string last_message; + + protected: /** * \brief Set Driver Id * @@ -80,9 +99,6 @@ class IriBaseDriver : public driver_base::Driver */ void setDriverId(const std::string & id); -// typedef boost::function< void() > hookFunction; - hookFunction preCloseHook; - public: /** * \brief Constructor @@ -115,42 +131,6 @@ class IriBaseDriver : public driver_base::Driver */ bool try_enter(void); - /** - * \brief Generic Open Driver - * - * Currently only changes the ROS driver state to open and calls the abstract - * function openDriver(). Common actions required for opening any kind of - * drivers should be added here. - */ - void doOpen(void); - - /** - * \brief Generic Close Driver - * - * Currently only changes the ROS driver state to close and calls the abstract - * function closeDriver(). Common actions required for opening any kind of - * drivers should be added here. - */ - void doClose(void); - - /** - * \brief Generic Start Driver - * - * Currently only changes the ROS driver state to start and calls the abstract - * function startDriver().Common actions required for opening any kind of - * drivers should be added here. - */ - void doStart(void); - - /** - * \brief Generic Stop Driver - * - * Currently only changes the ROS driver state to stop and calls the abstract - * function stopDriver(). Common actions required for opening any kind of - * drivers should be added here. - */ - void doStop(void); - /** * \brief Get Driver Id * @@ -162,6 +142,22 @@ class IriBaseDriver : public driver_base::Driver */ std::string getID(void); + bool goState(state_t target_state); + + state_t getState(void); + + std::string getStateName(void); + + std::string getStatusMessage(void); + + bool isRunning(void); + + bool isOpened(void); + + bool isClosed(void); + + bool isStopped(void); + /** * \brief User Open Driver * @@ -204,8 +200,13 @@ class IriBaseDriver : public driver_base::Driver */ virtual bool stopDriver(void) = 0; - - void setPreCloseHook(hookFunction f); + void setPostOpenHook(boost::function< void() > function); + + void setPreCloseHook(boost::function< void() > function); + + void setPostStartHook(boost::function< void() > function); + + void setPreStopHook(boost::function< void() > function); /** * \brief Destructor diff --git a/include/iri_base_driver/iri_base_driver_node.h b/include/iri_base_driver/iri_base_driver_node.h index cdbee840ac9b6f4debd347d564575d98843f0b4a..7225f9c427d60774057d5f2e14fb8f91552160bb 100644 --- a/include/iri_base_driver/iri_base_driver_node.h +++ b/include/iri_base_driver/iri_base_driver_node.h @@ -19,19 +19,36 @@ #ifndef _IRI_BASE_DRIVER_NODE_H #define _IRI_BASE_DRIVER_NODE_H -// ros base driver node, diagnostics, and iri_ros driver -#include <driver_base/driver_node.h> +#include <ros/ros.h> +#include <signal.h> + +// boost thread includes for ROS::spin thread +#include <boost/thread.hpp> +#include <boost/bind.hpp> + +// dynamic reconfigure server include +#include <dynamic_reconfigure/server.h> +#include <iri_base_driver/SensorLevels.h> + +// diagnostic updater include #include <diagnostic_updater/diagnostic_updater.h> -#include "iri_base_driver.h" + +#include "iri_base_driver/iri_base_driver.h" namespace iri_base_driver { + /** + * \brief default main thread frequency + * + * This constant determines the default frequency of the mainThread() in HZ. + * All nodes will loop at this rate if loop_rate_ variable is not modified. + */ + static const double DEFAULT_RATE = 10.0; //[Hz] /** * \brief IRI ROS Base Node Class * - * This class inherits from the ROS class driver_base::DriverNode<TemplateDriver> - * to provide an execution thread to the driver object. The TemplateDriver object + * This class provides the base class for any ROS driver. The Driver object * must be an implementation of the IriBaseDriver class. The inherit template * design form allows complete access to the driver object while manteining * flexibility to instantiate any object inherit from IriBaseDriver. @@ -46,21 +63,38 @@ namespace iri_base_driver * 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. + * Similarly, functions such as addDiagnostics() are prepared for detailing + * common features for all driver nodes while executing specific commands for + * each specification by calling the respective function addNodeDiagnostics() + * from the inherit node implementation. * * Instances of both IriBaseDriver 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. + * through ROS topics by using those scripts. The scripts can be downloaded + * from the IRI GitLab respository (See http://wiki.iri.upc.edu). */ template <class Driver> -class IriBaseNodeDriver : public driver_base::DriverNode<Driver> +class IriBaseNodeDriver { - protected: + public: + /** + * \brief config object + * + * All template driver class will need a Config variable to allow ROS + * dynamic reconfigure. This config class will contain all driver + * parameters which may be modified once the driver node is launched. + */ + typedef typename Driver::Config Config; + + private: + /** + * \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> spin_thread_; + /** * \brief Thread information structure * @@ -69,7 +103,23 @@ class IriBaseNodeDriver : public driver_base::DriverNode<Driver> * be modified at any time and it is not accessible from outside the class. * */ - pthread_t thread; + pthread_t main_thread; + + /** + * \brief main thread loop rate + * + * This value determines the loop frequency of the node main thread function + * mainThread() in Hz. It is initialized at construction time. This variable + * may be modified in the node implementation constructor if a desired + * frequency is required. + */ + ros::Rate loop_rate_; + + /** + * \brief + * + */ + diagnostic_updater::FunctionDiagnosticTask driver_status_standard_diagnostic_; /** * \brief main node post open hook @@ -79,14 +129,6 @@ class IriBaseNodeDriver : public driver_base::DriverNode<Driver> */ void postOpenHook(void); - /** - * \brief node implementation post open hook - * - * Abstrac function called by postOpenHook() that adds the specific driver - * node parameters to the dynamic reconfigure application. - */ - virtual void postNodeOpenHook(void) = 0; - /** * \brief main node pre close hook * @@ -94,129 +136,136 @@ class IriBaseNodeDriver : public driver_base::DriverNode<Driver> void preCloseHook(void); /** - * \brief node implementation pre close hook - * + * \brief main node post start hook + * */ - virtual void preNodeCloseHook(void); + void postStartHook(void); /** - * \brief public node handle communication object + * \brief main node pre stop hook * - * 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 public_node_handle_; + void preStopHook(void); /** - * \brief main thread loop rate + * \brief dynamic reconfigure server callback * - * This value determines the loop frequency of the node main thread function - * mainThread() in HZ. It is initialized at construction time. This variable - * may be modified in the node implementation constructor if a desired - * frequency is required. + * This method is called whenever a new configuration is received through + * the dynamic reconfigure. The derivated generic driver class must + * implement it. + * + * \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. */ - ros::Rate loop_rate_; + void reconfigureCallback(Config &config, uint32_t level); /** - * \brief default main thread frequency - * - * This constant determines the default frequency of the mainThread() in HZ. - * All nodes will loop at this rate if loop_rate_ variable is not modified. + * \brief main node add diagnostics + * + * In this function ROS diagnostics applied to all node may be added. + * */ - static const unsigned int DEFAULT_RATE = 10; //[Hz] + void addDiagnostics(void); - public: + protected: /** - * \brief constructor - * - * This constructor creates and initializes the main thread of the class. It - * also sets the driver_base::postOpenHook thread. NodeHandle and loop_rate_ - * variables are also initialized. + * \brief template driver class * - * \param nh a reference to the node handle object to manage all ROS topics. + * This template class refers to an implementation of an specific driver + * interface. Will be used in the derivate class to define the common + * behaviour for all the different implementations from the same driver. */ - IriBaseNodeDriver(ros::NodeHandle& nh); + Driver driver_; /** - * \brief destructor + * \brief public node handle communication object * - * This destructor closes the driver object and kills the main thread. + * 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. */ - ~IriBaseNodeDriver(); + ros::NodeHandle public_node_handle_; /** - * \brief main node add diagnostics - * - * In this function ROS diagnostics applied to all node may be added. + * \brief private node handle object * + * This private node handle will be used to define algorithm parameters into + * the ROS parametre server. For communication pruposes please use the + * previously defined node_handle_ object. */ - void addDiagnostics(void); + ros::NodeHandle private_node_handle_; /** - * \brief open status driver main node tests - * - * In this function tests checking driver's functionallity in driver_base - * status=open can be added. + * \brief dynamic reconfigure server + * + * The dynamic reconfigure server is in charge to retrieve the parameters + * defined in the config cfg file through the reconfigureCallback. */ - void addOpenedTests(void); + dynamic_reconfigure::Server<Config> dsrv_; /** - * \brief stop status driver main node tests - * - * In this function tests checking driver's functionallity in driver_base - * status=stop can be added. + * \brief diagnostic updater + * + * The diagnostic updater allows definition of custom diagnostics. + * */ - void addStoppedTests(void); + diagnostic_updater::Updater diagnostic_; /** - * \brief run status driver main node tests - * - * In this function tests checking driver's functionallity in driver_base - * status=run can be added. + * \brief + * */ - void addRunningTests(void); + void statusDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& stat); /** - * \brief main node dynamic reconfigure - * + * \brief node implementation post open hook * - * \param level integer + * Abstrac function called by postOpenHook() that adds the specific driver + * node parameters to the dynamic reconfigure application. */ - void reconfigureHook(int level); + virtual void postNodeOpenHook(void); - protected: /** - * \brief node add diagnostics - * - * In this abstract function additional ROS diagnostics applied to the - * specific node may be added. + * \brief node implementation pre close hook + * */ - virtual void addNodeDiagnostics(void) = 0; + virtual void preNodeCloseHook(void); /** - * \brief open status driver specific node tests - * - * In this abstract function tests checking driver's functionallity in - * driver_base status=open can be added. + * \brief node implementation post start hook + * */ - virtual void addNodeOpenedTests(void) = 0; + virtual void postNodeStartHook(void); /** - * \brief stop status driver specific node tests + * \brief node implementation pre stop hook + * + */ + virtual void preNodeStopHook(void); + + /** + * \brief dynamic reconfigure server callback + * + * This method is called whenever a new configuration is received through + * the dynamic reconfigure. The derivated generic driver class must + * implement it. * - * In this abstract function tests checking driver's functionallity in - * driver_base status=stop can be added. + * \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. */ - virtual void addNodeStoppedTests(void) = 0; + virtual void node_config_update(Config &config, uint32_t level); /** - * \brief run status driver specific node tests + * \brief node add diagnostics * - * In this abstract function tests checking driver's functionallity in - * driver_base status=run can be added. + * In this abstract function additional ROS diagnostics applied to the + * specific node may be added. */ - virtual void addNodeRunningTests(void) = 0; + virtual void addNodeDiagnostics(void) = 0; /** * \brief main node thread @@ -242,29 +291,66 @@ class IriBaseNodeDriver : public driver_base::DriverNode<Driver> virtual void mainNodeThread(void) = 0; /** - * \brief specific node dynamic reconfigure + * \brief + * + */ + void setRate(double rate_hz); + + /** + * \brief + * + */ + double getRate(void); + + static void hupCalled(int sig); + + public: + + /** + * \brief constructor * - * This function is called reconfigureHook() + * This constructor creates and initializes the main thread of the class. It + * also sets the driver_base::postOpenHook thread. NodeHandle and loop_rate_ + * variables are also initialized. + * + */ + IriBaseNodeDriver(const ros::NodeHandle &nh = ros::NodeHandle("~")); + + /** + * \brief spin * - * \param level integer + * 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. */ - virtual void reconfigureNodeHook(int level) = 0; + int spin(void); + + /** + * \brief destructor + * + * This destructor closes the driver object and kills the main thread. + */ + ~IriBaseNodeDriver(); }; template <class Driver> -IriBaseNodeDriver<Driver>::IriBaseNodeDriver(ros::NodeHandle &nh) : - driver_base::DriverNode<Driver>(nh), - public_node_handle_(ros::this_node::getName()), - loop_rate_(DEFAULT_RATE) +IriBaseNodeDriver<Driver>::IriBaseNodeDriver(const ros::NodeHandle &nh) : + public_node_handle_(nh), + loop_rate_(DEFAULT_RATE), + diagnostic_(), + dsrv_(private_node_handle_), + private_node_handle_("~"), + driver_status_standard_diagnostic_("Driver Status", boost::bind(&IriBaseNodeDriver::statusDiagnostic, this, _1)) { ROS_DEBUG("IriBaseNodeDriver::Constructor"); this->driver_.setPostOpenHook(boost::bind(&IriBaseNodeDriver::postOpenHook, this)); - this->driver_.setPreCloseHook(boost::bind(&IriBaseNodeDriver::preNodeCloseHook, this)); - - // create the status thread - pthread_create(&this->thread,NULL,this->mainThread,this); + this->driver_.setPreCloseHook(boost::bind(&IriBaseNodeDriver::preCloseHook, this)); + this->driver_.setPostStartHook(boost::bind(&IriBaseNodeDriver::postStartHook, this)); + this->driver_.setPreStopHook(boost::bind(&IriBaseNodeDriver::preStopHook, this)); // initialize class attributes + // allow Ctrl+C management + signal(SIGHUP, &IriBaseNodeDriver<Driver>::hupCalled); } template <class Driver> @@ -276,20 +362,26 @@ void *IriBaseNodeDriver<Driver>::mainThread(void *param) while(ros::ok()) { -// std::cout << __LINE__ << ": driver state=" << iriNode->driver_.getStateName() << std::endl; if(iriNode->driver_.isRunning()) - { iriNode->mainNodeThread(); - -// ros::spinOnce(); - } iriNode->loop_rate_.sleep(); - } pthread_exit(NULL); } +template <class Driver> +void IriBaseNodeDriver<Driver>::setRate(double rate_hz) +{ + this->loop_rate_=ros::Rate(rate_hz); +} + +template <class Driver> +double IriBaseNodeDriver<Driver>::getRate(void) +{ + return 1.0/this->loop_rate_.expectedCycleTime().toSec(); +} + template <class Driver> void IriBaseNodeDriver<Driver>::postOpenHook(void) { @@ -298,54 +390,176 @@ void IriBaseNodeDriver<Driver>::postOpenHook(void) //set hardware id with driver id this->diagnostic_.setHardwareID(this->driver_.getID()); - postNodeOpenHook(); + /* call the inherited class post open function */ + this->postNodeOpenHook(); +} + +template <class Driver> +void IriBaseNodeDriver<Driver>::postNodeOpenHook(void) +{ + } template <class Driver> void IriBaseNodeDriver<Driver>::preCloseHook(void) { - ROS_INFO("IriBaseNodeDriver::preCloseHook"); - preNodeCloseHook(); + ROS_DEBUG("IriBaseNodeDriver::preCloseHook"); + /* call the inherited class pre close function */ + this->preNodeCloseHook(); } template <class Driver> void IriBaseNodeDriver<Driver>::preNodeCloseHook(void) { + } - + template <class Driver> -void IriBaseNodeDriver<Driver>::addDiagnostics(void) +void IriBaseNodeDriver<Driver>::postStartHook(void) { - ROS_DEBUG("IriBaseNodeDriver::addDiagnostics"); - addNodeDiagnostics(); + ROS_DEBUG("IriBaseNodeDriver::postStartHook"); + /* call the inherited class post start function */ + this->postNodeStartHook(); +} + +template <class Driver> +void IriBaseNodeDriver<Driver>::postNodeStartHook(void) +{ + +} + +template <class Driver> +void IriBaseNodeDriver<Driver>::preStopHook(void) +{ + ROS_DEBUG("IriBaseNodeDriver::preStopHook"); + /* call the inherited class pre stop function */ + this->preNodeStopHook(); } template <class Driver> -void IriBaseNodeDriver<Driver>::addOpenedTests(void) +void IriBaseNodeDriver<Driver>::preNodeStopHook(void) { - ROS_DEBUG("IriBaseNodeDriver::addOpenedTests"); - addNodeOpenedTests(); + +} + +template <class Driver> +void IriBaseNodeDriver<Driver>::node_config_update(Config &config, uint32_t level) +{ + } template <class Driver> -void IriBaseNodeDriver<Driver>::addStoppedTests(void) +void IriBaseNodeDriver<Driver>::statusDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& stat) { - ROS_DEBUG("IriBaseNodeDriver::addStoppedTests"); - addNodeStoppedTests(); + if (driver_.isRunning()) + stat.summary(0, "OK"); + else + stat.summary(2, "not running"); + + stat.add("Driver state:", this->driver_.getStateName()); + stat.add("Latest status message:", this->driver_.getStatusMessage()); } template <class Driver> -void IriBaseNodeDriver<Driver>::addRunningTests(void) +void IriBaseNodeDriver<Driver>::addDiagnostics(void) { - ROS_DEBUG("IriBaseNodeDriver::addRunningTests"); - addNodeRunningTests(); + ROS_DEBUG("IriBaseNodeDriver::addDiagnostics"); + this->diagnostic_.add(this->driver_status_standard_diagnostic_); + + /* add the inherited class diagnostics */ + this->addNodeDiagnostics(); +} + +template <class Driver> +void IriBaseNodeDriver<Driver>::reconfigureCallback(Config &config, uint32_t level) +{ + iri_base_driver::state_t original_state; + + /// @todo Move this into the Driver class? + ROS_DEBUG("IriBaseNodeDriver::reconfigureCallback"); + + original_state=this->driver_.getState(); + /* go to the desired state for the update */ + switch(level) + { + case iri_base_driver::SensorLevels::RECONFIGURE_STOP: + this->driver_.goState(iri_base_driver::OPENED); + break; + case iri_base_driver::SensorLevels::RECONFIGURE_CLOSE: + this->driver_.goState(iri_base_driver::CLOSED); + break; + case iri_base_driver::SensorLevels::RECONFIGURE_RUNNING: + this->driver_.goState(iri_base_driver::RUNNING); + break; + } + + /* update the driver */ + this->driver_.config_update(config, level); + /* update the node */ + this->node_config_update(config, level); + + /* return to the previous state */ + this->driver_.goState(original_state); +} + +template <class Driver> +int IriBaseNodeDriver<Driver>::spin(void) +{ + ROS_DEBUG("IriBaseNodeDriver::spin"); + + // initialize diagnostics + this->addDiagnostics(); + + // launch ros spin in different thread + this->spin_thread_.reset(new boost::thread(boost::bind(&ros::spin))); + assert(spin_thread_); + + // initial call of the reconfigure callback function +// this->reconfigureCallback(this->driver_.config_,iri_base_driver::SensorLevels::RECONFIGURE_CLOSE); + // assign callback to dynamic reconfigure server + this->dsrv_.setCallback(boost::bind(&IriBaseNodeDriver<Driver>::reconfigureCallback, this, _1, _2)); + + // create the status thread + pthread_create(&this->main_thread,NULL,this->mainThread,this); + + // try to go to the running state + this->driver_.goState(iri_base_driver::RUNNING); + + while(ros::ok()) + { + if (!this->driver_.isRunning()) + { + ros::WallDuration(1).sleep(); + this->driver_.goState(iri_base_driver::CLOSED); + this->driver_.goState(iri_base_driver::RUNNING); + } + // update diagnostics + this->diagnostic_.update(); + + ros::WallDuration(0.1).sleep(); + } + + // try to go to the closed state + this->driver_.goState(iri_base_driver::CLOSED); + + // stop ros + ros::shutdown(); + + if (this->spin_thread_ && !this->spin_thread_->timed_join((boost::posix_time::milliseconds) 2000)) + { + ROS_ERROR("ROS thread did not die after two seconds. Pretending that it did. This is probably a bad sign."); + } + + // kill ros spin thread + this->spin_thread_.reset(); + + return 0; } template <class Driver> -void IriBaseNodeDriver<Driver>::reconfigureHook(int level) +void IriBaseNodeDriver<Driver>::hupCalled(int sig) { - ROS_DEBUG("IriBaseNodeDriver::reconfigureHook"); - reconfigureNodeHook(level); + ROS_WARN("Unexpected SIGHUP caught. Ignoring it."); } template <class Driver> @@ -354,12 +568,40 @@ IriBaseNodeDriver<Driver>::~IriBaseNodeDriver() ROS_DEBUG("IriBaseNodeDriver::Destrcutor"); //try access to driver to assert it is //unlock before its destruction - this->driver_.try_enter(); - this->driver_.unlock(); - this->driver_.close(); - pthread_cancel(this->thread); - pthread_join(this->thread,NULL); + this->driver_.goState(iri_base_driver::CLOSED); + pthread_cancel(this->main_thread); + pthread_join(this->main_thread,NULL); +} + +/** + * \brief base main + * + * This main is common for all the driver nodes. The DriverType class + * refers to an specific implementation derived from a generic driver. + * + * First, ros::init is called providing the node name. Ctrl+C control is + * activated for sercure and safe exit. Finally, a DriverType 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 DriverType> +int main(int argc, char **argv, std::string node_name) +{ + ROS_DEBUG("IriBaseDriver::%s Launched", node_name.c_str()); + + // ROS initialization + ros::init(argc, argv, node_name); + + // define and launch generic algorithm implementation object + ros::NodeHandle nh; + DriverType driver(nh); + driver.spin(); + + return 0; } } diff --git a/msg/SensorLevels.msg b/msg/SensorLevels.msg new file mode 100644 index 0000000000000000000000000000000000000000..5502f4c46535b006c19364d7de99f0293f55b6c9 --- /dev/null +++ b/msg/SensorLevels.msg @@ -0,0 +1,4 @@ +byte RECONFIGURE_CLOSE = 3 # Parameters that need a sensor to be stopped completely when changed +byte RECONFIGURE_STOP = 1 # Parameters that need a sensor to stop streaming when changed +byte RECONFIGURE_RUNNING = 0 # Parameters that can be changed while a sensor is streaming + diff --git a/package.xml b/package.xml index 4b3baf87c2c552fde5cc19c1731a24b11b34f344..b3acafa1aa4d64fcae74ee533a8bf4bb1478659c 100644 --- a/package.xml +++ b/package.xml @@ -1,49 +1,25 @@ <?xml version="1.0"?> -<package> +<package format="2"> <name>iri_base_driver</name> <version>1.0.0</version> <description>The iri_base_driver package</description> - <!-- One maintainer tag required, multiple allowed, one person per tag --> - <!-- Example: --> - <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> --> <maintainer email="labrobotica@iri.upc.edu">labrobotica</maintainer> - - <!-- One license tag required, multiple allowed, one license per tag --> - <!-- Commonly used license strings: --> - <!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 --> <license>LGPL</license> - - <!-- Url tags are optional, but mutiple are allowed, one per tag --> - <!-- Optional attribute type can be: website, bugtracker, or repository --> - <!-- Example: --> <url type="website">http://wiki.ros.org/iri_base_driver</url> - - <!-- Author tags are optional, mutiple are allowed, one per tag --> - <!-- Authors do not have to be maintianers, but could be --> - <!-- Example: --> - <!-- <author email="jane.doe@example.com">Jane Doe</author> --> <author>Joan Perez</author> - - <!-- The *_depend tags are used to specify dependencies --> - <!-- Dependencies can be catkin packages or system dependencies --> - <!-- Examples: --> - <!-- Use build_depend for packages you need at compile time: --> - <build_depend>roscpp</build_depend> - <build_depend>driver_base</build_depend> - <build_depend>dynamic_reconfigure</build_depend> - <!-- Use buildtool_depend for build tool packages: --> - <!-- <buildtool_depend>catkin</buildtool_depend> --> - <!-- Use run_depend for packages you need at runtime: --> - <run_depend>roscpp</run_depend> - <run_depend>driver_base</run_depend> - <run_depend>dynamic_reconfigure</run_depend> - <!-- Use test_depend for packages you need only for testing: --> - <!-- <test_depend>gtest</test_depend> --> <buildtool_depend>catkin</buildtool_depend> + <depend>roscpp</depend> + <depend>dynamic_reconfigure</depend> + <depend>message_runtime</depend> + + <!-- The export tag contains other, unspecified, tags --> + <export> + <!-- Other tools can request additional information be placed here --> + </export> </package> diff --git a/src/iri_base_driver.cpp b/src/iri_base_driver.cpp index 984f667e0f70e6cb852336486b0f0c4cb1933d31..99a129d3afcb02be689a3bf8c21424de32a1108c 100644 --- a/src/iri_base_driver.cpp +++ b/src/iri_base_driver.cpp @@ -3,9 +3,13 @@ namespace iri_base_driver { -IriBaseDriver::IriBaseDriver() : driver_id_("none") +IriBaseDriver::IriBaseDriver() { + this->current_state_=iri_base_driver::CLOSED; + this->driver_id_="none"; + this->last_message="not operational yet"; pthread_mutex_init(&this->access_,NULL); + pthread_mutex_init(&this->internal_access_,NULL); } void IriBaseDriver::lock(void) @@ -31,40 +35,232 @@ void IriBaseDriver::setDriverId(const std::string & id) driver_id_ = id; } -void IriBaseDriver::doOpen(void) +std::string IriBaseDriver::getID(void) { - if(openDriver()) this->state_ = OPENED; + return this->driver_id_; } -void IriBaseDriver::doClose(void) +bool IriBaseDriver::goState(state_t target_state) { - this->preCloseHook(); - if(closeDriver()) this->state_ = CLOSED; + std::string transition; + bool error=false; + + pthread_mutex_lock(&this->internal_access_); + try{ + do{ + switch(this->current_state_) + { + case iri_base_driver::CLOSED: if(target_state == iri_base_driver::OPENED || target_state == iri_base_driver::RUNNING) + { + transition="open"; + ROS_DEBUG("Trying transition open from CLOSED to OPENED."); + if(this->openDriver()) + { + this->current_state_=iri_base_driver::OPENED; + this->postOpenHook(); + this->last_message="Transition open from CLOSED to OPENED succeeded."; + ROS_DEBUG("%s",this->last_message.c_str()); + } + else + { + this->current_state_=iri_base_driver::CLOSED; + this->last_message="Transition open from CLOSED to OPENED failed."; + ROS_DEBUG("%s",this->last_message.c_str()); + error=true; + } + } + else + { + this->current_state_=iri_base_driver::CLOSED; + this->last_message="No transition required"; + ROS_DEBUG("%s",this->last_message.c_str()); + } + break; + case iri_base_driver::OPENED: if(target_state == iri_base_driver::CLOSED) + { + transition="close"; + ROS_DEBUG("Trying transition close from OPENED to CLOSED."); + this->preCloseHook(); + if(this->closeDriver()) + { + this->current_state_=iri_base_driver::CLOSED; + this->last_message="Transition close from OPENED to CLOSED succeeded."; + ROS_DEBUG("%s",this->last_message.c_str()); + } + else + { + this->current_state_=iri_base_driver::OPENED; + this->last_message="Transition close from OPENED to CLOSED failed."; + ROS_DEBUG("%s",this->last_message.c_str()); + error=true; + } + } + else if(target_state == iri_base_driver::RUNNING) + { + transition="start"; + ROS_DEBUG("Trying transition start from OPENED to RUNNING."); + if(this->startDriver()) + { + this->current_state_=iri_base_driver::RUNNING; + this->last_message="Transition start from OPENED to RUNNING succeeded."; + ROS_DEBUG("%s",this->last_message.c_str()); + } + else + { + this->current_state_=iri_base_driver::OPENED; + this->last_message="Transition start from OPENED to RUNNING failed."; + ROS_DEBUG("%s",this->last_message.c_str()); + error=true; + } + } + else + { + this->current_state_=iri_base_driver::OPENED; + this->last_message="No transition required"; + ROS_DEBUG("%s",this->last_message.c_str()); + } + break; + case RUNNING: if(target_state == iri_base_driver::OPENED || target_state == iri_base_driver::CLOSED) + { + transition="stop"; + ROS_DEBUG("Trying transition stop from RUNNING to OPENED."); + if(this->stopDriver()) + { + this->current_state_=iri_base_driver::OPENED; + this->last_message="Transition stop from RUNING to OPENED succeeded."; + ROS_DEBUG("%s",this->last_message.c_str()); + } + else + { + this->current_state_=iri_base_driver::RUNNING; + this->last_message="Transition stop from RUNNING to OPENED failed."; + ROS_DEBUG("%s",this->last_message.c_str()); + error=true; + } + } + else + { + this->current_state_=iri_base_driver::RUNNING; + this->last_message="No transition required"; + ROS_DEBUG("%s",this->last_message.c_str()); + } + break; + } + }while(!error && this->current_state_!=target_state); + }catch(...){ + ROS_WARN("Caught exception in state transition %s\n",transition.c_str()); + error=true; + } + pthread_mutex_unlock(&this->internal_access_); + + return error; } -void IriBaseDriver::doStart(void) +state_t IriBaseDriver::getState(void) { - if(startDriver()) this->state_ = RUNNING; + return this->current_state_; } -void IriBaseDriver::doStop(void) +std::string IriBaseDriver::getStateName(void) { - if(stopDriver()) this->state_ = OPENED; + switch(this->current_state_) + { + case iri_base_driver::CLOSED: return std::string("closed"); + case iri_base_driver::OPENED: return std::string("opened"); + case iri_base_driver::RUNNING: return std::string("running"); + default: return std::string("default value: not_possible"); + } } -std::string IriBaseDriver::getID(void) +std::string IriBaseDriver::getStatusMessage(void) +{ + return this->last_message; +} + +bool IriBaseDriver::isRunning(void) +{ + pthread_mutex_lock(&this->internal_access_); + if(this->current_state_ == iri_base_driver::RUNNING) + { + pthread_mutex_unlock(&this->internal_access_); + return true; + } + else + { + pthread_mutex_unlock(&this->internal_access_); + return false; + } +} + +bool IriBaseDriver::isOpened(void) +{ + pthread_mutex_lock(&this->internal_access_); + if(this->current_state_ == iri_base_driver::OPENED) + { + pthread_mutex_unlock(&this->internal_access_); + return true; + } + else + { + pthread_mutex_unlock(&this->internal_access_); + return false; + } +} + +bool IriBaseDriver::isClosed(void) +{ + pthread_mutex_lock(&this->internal_access_); + if(this->current_state_ == iri_base_driver::CLOSED) + { + pthread_mutex_unlock(&this->internal_access_); + return true; + } + else + { + pthread_mutex_unlock(&this->internal_access_); + return false; + } +} + +bool IriBaseDriver::isStopped(void) +{ + pthread_mutex_lock(&this->internal_access_); + if(this->current_state_ == iri_base_driver::OPENED || this->current_state_ == iri_base_driver::CLOSED) + { + pthread_mutex_unlock(&this->internal_access_); + return true; + } + else + { + pthread_mutex_unlock(&this->internal_access_); + return false; + } +} + +void IriBaseDriver::setPostOpenHook(boost::function< void() > function) +{ + this->postOpenHook = function; +} + +void IriBaseDriver::setPreCloseHook(boost::function< void() > function) +{ + this->preCloseHook = function; +} + +void IriBaseDriver::setPostStartHook(boost::function< void() > function) { - return driver_id_; + this->postStartHook = function; } -void IriBaseDriver::setPreCloseHook(hookFunction f) +void IriBaseDriver::setPreStopHook(boost::function< void() > function) { - preCloseHook = f; + this->preStopHook = function; } IriBaseDriver::~IriBaseDriver() { pthread_mutex_destroy(&this->access_); + pthread_mutex_destroy(&this->internal_access_); } }