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

Migrated the iri_base_algorithm to the catkin framework.

Changes to the iri_base_driver package for correct compilation under catkin. 
parents
No related branches found
No related tags found
No related merge requests found
cmake_minimum_required(VERSION 2.8.3)
project(iri_base_algorithm)
## 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)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependencies might have been
## pulled in transitively but can be declared for certainty nonetheless:
## * add a build_depend tag for "message_generation"
## * add a run_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * 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
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# std_msgs # Or other packages containing msgs
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS roscpp driver_base dynamic_reconfigure
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
# include_directories(include)
## Declare a cpp library
# add_library(foo
# src/${PROJECT_NAME}/foo.cpp
# )
## Declare a cpp executable
# add_executable(foo_node src/foo_node.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)
## Specify libraries to link a library or executable target against
# target_link_libraries(foo_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
# install(TARGETS foo foo_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_foo.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
// Author Joan Perez
// All rights reserved.
//
// 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.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU Lesser General Public License for more details.
//
// 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/>.
#ifndef _IRI_BASE_ALGORITHM_H
#define _IRI_BASE_ALGORITHM_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>
// diagnostic updater include
#include <diagnostic_updater/diagnostic_updater.h>
namespace algorithm_base
{
/**
* \brief Abstract Class for Ctrl+C management
*
*/
class AbstractAlgorithmNode
{
protected:
static int ctrl_c_hit_count_;
static void hupCalled(int sig)
{
ROS_WARN("Unexpected SIGHUP caught. Ignoring it.");
}
static void sigCalled(int sig)
{
ctrl_c_hit_count_++;
}
};
/**
* \brief IRI ROS Algorithm Base Node Class
*
* This class provides a common framework for all kind of algorithms, similar to
* the one defined for the ROS driver_base::DriverNode<TemplateDriver> for the
* driver environment. In this case, the template Algorithm class must be an
* implementation derivated from a common interface (preferably ROS defined).
* The inherit template design form allows complete access to the generic
* algorithm object while manteining flexibility to instantiate any object which
* inherits from it.
*
* An abstract class is generated as a ROS package to force implementation of
* virtual methods in the generic algorithm layer. Functions to perform tests,
* add diagnostics or dynamically reconfigure the algorithm parameters are
* offered respecting the ROS driver_base terminology. Similarly to the
* IriBaseNodeDriver common purpose behaviours for all algorithm kinds can be
* defined and forwarded to each of the generic algorithm classes for specific
* operations.
*
* In addition, a mainThread is provided like in the IriBaseNodeDriver class.
* Threads are implemented using iri_utils software utilities. The mainThread()
* function loops in a defined loop_rate_. In each iteration, the abstract
* mainNodeThread() function defined in the inherit node class is called.
*/
template <class Algorithm>
class IriBaseAlgorithm : public AbstractAlgorithmNode
{
public:
/**
* \brief config object
*
* All template Algorithm class will need a Config variable to allow ROS
* dynamic reconfigure. This config class will contain all algorithm
* parameters which may be modified once the algorithm node is launched.
*/
typedef typename Algorithm::Config Config;
protected:
/**
* \brief Thread information structure
*
* This structure hold system level information of the thread and it is
* initialized when the thread is first created. This information can not
* be modified at any time and it is not accessible from outside the class.
*
*/
pthread_t thread;
/**
* \brief template algorithm class
*
* This template class refers to an implementation of an specific algorithm
* interface. Will be used in the derivate class to define the common
* behaviour for all the different implementations from the same algorithm.
*/
Algorithm alg_;
/**
* \brief public node handle communication object
*
* 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_;
/**
* \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.
*/
ros::NodeHandle private_node_handle_;
/**
* \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 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 unsigned int DEFAULT_RATE = 10; //[Hz]
/**
* \brief diagnostic updater
*
* The diagnostic updater allows definition of custom diagnostics.
*
*/
diagnostic_updater::Updater diagnostic_;
public:
/**
* \brief constructor
*
* This constructor initializes all the node handle objects, the main thread
* loop_rate_ and the diagnostic updater. It also instantiates the main
* thread of the class and the dynamic reconfigure callback.
*/
IriBaseAlgorithm(void);
/**
* \brief destructor
*
* This destructor kills the main thread.
*/
~IriBaseAlgorithm(void);
/**
* \brief spin
*
* 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.
*/
int spin(void);
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> ros_thread_;
/**
* \brief dynamic reconfigure server
*
* The dynamic reconfigure server is in charge to retrieve the parameters
* defined in the config cfg file through the reconfigureCallback.
*/
dynamic_reconfigure::Server<Config> dsrv_;
protected:
/**
* \brief dynamic reconfigure server callback
*
* This method is called whenever a new configuration is received through
* the dynamic reconfigure. The derivated generic algorithm 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.
*/
void reconfigureCallback(Config &config, uint32_t level);
/**
* \brief dynamic reconfigure server callback
*
* This method is called whenever a new configuration is received through
* the dynamic reconfigure. The derivated generic algorithm 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.
*/
virtual void node_config_update(Config &config, uint32_t level) = 0;
/**
* \brief add diagnostics
*
* In this function ROS diagnostics applied to all algorithms nodes may be
* added. It calls the addNodeDiagnostics method.
*/
void addDiagnostics(void);
/**
* \brief node add diagnostics
*
* In this abstract function additional ROS diagnostics applied to the
* specific algorithms may be added.
*/
virtual void addNodeDiagnostics(void) = 0;
// void addOpenedTests(void);
// void addStoppedTests(void);
// void addRunningTests(void);
// virtual void addNodeOpenedTests(void) = 0;
// virtual void addNodeStoppedTests(void) = 0;
// virtual void addNodeRunningTests(void) = 0;
/**
* \brief main node thread
*
* This is the main thread node function. Code written here will be executed
* in every inherit algorithm node object. The loop won't exit until the node
* finish its execution. The commands implemented in the abstract function
* mainNodeThread() will be executed in every iteration.
*
* Loop frequency can be tuned my modifying loop_rate_ attribute.
*
* \param param is a pointer to a IriBaseAlgorithm object class. It is used
* to access to the object attributes and methods.
*/
static void *mainThread(void *param);
/**
* \brief specific node thread
*
* In this abstract function specific commands for each algorithm node
* have to be detailed.
*/
virtual void mainNodeThread(void) = 0;
};
template <class Algorithm>
IriBaseAlgorithm<Algorithm>::IriBaseAlgorithm() :
public_node_handle_(ros::this_node::getName()),
private_node_handle_("~"),
loop_rate_(DEFAULT_RATE),
diagnostic_(),
dsrv_(private_node_handle_)
{
ROS_DEBUG("IriBaseAlgorithm::Constructor");
// // assign callback to dynamic reconfigure server
// dsrv_.setCallback(boost::bind(&IriBaseAlgorithm<Algorithm>::reconfigureCallback, this, _1, _2));
}
template <class Algorithm>
IriBaseAlgorithm<Algorithm>::~IriBaseAlgorithm()
{
ROS_DEBUG("IriBaseAlgorithm::Destructor");
pthread_cancel(this->thread);
pthread_join(this->thread,NULL);
}
template <class Algorithm>
void IriBaseAlgorithm<Algorithm>::reconfigureCallback(Config &config, uint32_t level)
{
ROS_DEBUG("IriBaseAlgorithm::reconfigureCallback");
this->node_config_update(config, level);
this->alg_.config_update(config, level);
}
template <class Algorithm>
void IriBaseAlgorithm<Algorithm>::addDiagnostics(void)
{
ROS_DEBUG("IriBaseAlgorithm::addDiagnostics");
addNodeDiagnostics();
}
template <class Algorithm>
void *IriBaseAlgorithm<Algorithm>::mainThread(void *param)
{
ROS_DEBUG("IriBaseAlgorithm::mainThread");
// retrieve base algorithm class
IriBaseAlgorithm *iriNode = (IriBaseAlgorithm *)param;
while(ros::ok() && !ctrl_c_hit_count_)
{
// run node stuff
iriNode->mainNodeThread();
// sleep remainder time
iriNode->loop_rate_.sleep();
}
// kill main thread
pthread_exit(NULL);
}
template <class Algorithm>
int IriBaseAlgorithm<Algorithm>::spin(void)
{
ROS_DEBUG("IriBaseAlgorithm::spin");
// initialize diagnostics
this->diagnostic_.setHardwareID("none");
this->addDiagnostics();
// launch ros spin in different thread
this->ros_thread_.reset( new boost::thread(boost::bind(&ros::spin)) );
assert(ros_thread_);
// assign callback to dynamic reconfigure server
this->dsrv_.setCallback(boost::bind(&IriBaseAlgorithm<Algorithm>::reconfigureCallback, this, _1, _2));
// create the status thread
pthread_create(&this->thread,NULL,this->mainThread,this);
while(ros::ok() && !ctrl_c_hit_count_)
{
// update diagnostics
this->diagnostic_.update();
ros::WallDuration(0.1).sleep();
}
// stop ros
ros::shutdown();
// kill ros spin thread
this->ros_thread_.reset();
return 0;
}
// definition of the static Ctrl+C counter
int AbstractAlgorithmNode::ctrl_c_hit_count_ = 0;
/**
* \brief base main
*
* This main is common for all the algorithm nodes. The AlgImplTempl class
* refers to an specific implementation derived from a generic algorithm.
*
* First, ros::init is called providing the node name. Ctrl+C control is
* activated for sercure and safe exit. Finally, an AlgImplTempl 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 AlgImplTempl>
int main(int argc, char **argv, std::string node_name)
{
ROS_DEBUG("IriBaseAlgorithm::%s Launched", node_name.c_str());
// ROS initialization
ros::init(argc, argv, node_name);
// allow Ctrl+C management
signal(SIGHUP, &AbstractAlgorithmNode::hupCalled);
// define and launch generic algorithm implementation object
AlgImplTempl algImpl;
algImpl.spin();
return 0;
}
}
#endif
/**
\mainpage
\htmlinclude manifest.html
\b iri_base_algorithm is ...
<!--
Provide an overview of your package.
-->
\section codeapi Code API
<!--
Provide links to specific auto-generated API documentation within your
package that is of particular interest to a reader. Doxygen will
document pretty much every part of your code, so do your best here to
point the reader to the actual API.
If your codebase is fairly large or has different sets of APIs, you
should use the doxygen 'group' tag to keep these APIs together. For
example, the roscpp documentation has 'libros' group.
-->
*/
<?xml version="1.0"?>
<package>
<name>iri_base_algorithm</name>
<version>1.0.0</version>
<description>The iri_base_algorithm 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_algorithm</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>dynamic_reconfigure</build_depend>
<build_depend>diagnostic_updater</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>dynamic_reconfigure</run_depend>
<run_depend>diagnostic_updater</run_depend>
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<buildtool_depend>catkin</buildtool_depend>
</package>
<depend package="diagnostic_updater"/>
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