IRI ROS Algorithm Base Node Class. More...
#include <iri_base_algorithm.h>
Public Types | |
typedef Algorithm::Config | Config |
config object | |
Public Member Functions | |
IriBaseAlgorithm (void) | |
constructor | |
int | spin (void) |
spin | |
~IriBaseAlgorithm (void) | |
destructor | |
Protected Member Functions | |
void | addDiagnostics (void) |
add diagnostics | |
virtual void | addNodeDiagnostics (void)=0 |
node add diagnostics | |
virtual void | mainNodeThread (void)=0 |
specific node thread | |
virtual void | node_config_update (Config &config, uint32_t level)=0 |
dynamic reconfigure server callback | |
void | reconfigureCallback (Config &config, uint32_t level) |
dynamic reconfigure server callback | |
Static Protected Member Functions | |
static void * | mainThread (void *param) |
main node thread | |
Protected Attributes | |
Algorithm | alg_ |
template algorithm class | |
diagnostic_updater::Updater | diagnostic_ |
diagnostic updater | |
ros::Rate | loop_rate_ |
main thread loop rate | |
ros::NodeHandle | private_node_handle_ |
private node handle object | |
ros::NodeHandle | public_node_handle_ |
public node handle communication object | |
pthread_t | thread |
Thread information structure. | |
Static Protected Attributes | |
static const unsigned int | DEFAULT_RATE = 10 |
default main thread frequency | |
Private Attributes | |
dynamic_reconfigure::Server < Config > | dsrv_ |
dynamic reconfigure server | |
boost::shared_ptr< boost::thread > | ros_thread_ |
ros spin thread |
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.
Definition at line 83 of file iri_base_algorithm.h.
typedef Algorithm::Config algorithm_base::IriBaseAlgorithm< Algorithm >::Config |
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.
Definition at line 93 of file iri_base_algorithm.h.
algorithm_base::IriBaseAlgorithm< Algorithm >::IriBaseAlgorithm | ( | void | ) |
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.
Definition at line 280 of file iri_base_algorithm.h.
algorithm_base::IriBaseAlgorithm< Algorithm >::~IriBaseAlgorithm | ( | void | ) |
destructor
This destructor kills the main thread.
Definition at line 298 of file iri_base_algorithm.h.
void algorithm_base::IriBaseAlgorithm< Algorithm >::addDiagnostics | ( | void | ) | [protected] |
add diagnostics
In this function ROS diagnostics applied to all algorithms nodes may be added. It calls the addNodeDiagnostics method.
Definition at line 314 of file iri_base_algorithm.h.
virtual void algorithm_base::IriBaseAlgorithm< Algorithm >::addNodeDiagnostics | ( | void | ) | [protected, pure virtual] |
node add diagnostics
In this abstract function additional ROS diagnostics applied to the specific algorithms may be added.
virtual void algorithm_base::IriBaseAlgorithm< Algorithm >::mainNodeThread | ( | void | ) | [protected, pure virtual] |
specific node thread
In this abstract function specific commands for each algorithm node have to be detailed.
void * algorithm_base::IriBaseAlgorithm< Algorithm >::mainThread | ( | void * | param | ) | [static, protected] |
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 | is a pointer to a IriBaseAlgorithm object class. It is used to access to the object attributes and methods. |
Definition at line 321 of file iri_base_algorithm.h.
virtual void algorithm_base::IriBaseAlgorithm< Algorithm >::node_config_update | ( | Config & | config, |
uint32_t | level | ||
) | [protected, pure virtual] |
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.
config | an object with new configuration from all algorithm parameters defined in the config file. |
level | integer referring the level in which the configuration has been changed. |
void algorithm_base::IriBaseAlgorithm< Algorithm >::reconfigureCallback | ( | Config & | config, |
uint32_t | level | ||
) | [protected] |
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.
config | an object with new configuration from all algorithm parameters defined in the config file. |
level | integer referring the level in which the configuration has been changed. |
Definition at line 306 of file iri_base_algorithm.h.
int algorithm_base::IriBaseAlgorithm< Algorithm >::spin | ( | void | ) |
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.
Definition at line 342 of file iri_base_algorithm.h.
Algorithm algorithm_base::IriBaseAlgorithm< Algorithm >::alg_ [protected] |
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.
Definition at line 113 of file iri_base_algorithm.h.
const unsigned int algorithm_base::IriBaseAlgorithm< Algorithm >::DEFAULT_RATE = 10 [static, protected] |
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.
Definition at line 149 of file iri_base_algorithm.h.
diagnostic_updater::Updater algorithm_base::IriBaseAlgorithm< Algorithm >::diagnostic_ [protected] |
diagnostic updater
The diagnostic updater allows definition of custom diagnostics.
Definition at line 157 of file iri_base_algorithm.h.
dynamic_reconfigure::Server<Config> algorithm_base::IriBaseAlgorithm< Algorithm >::dsrv_ [private] |
dynamic reconfigure server
The dynamic reconfigure server is in charge to retrieve the parameters defined in the config cfg file through the reconfigureCallback.
Definition at line 200 of file iri_base_algorithm.h.
ros::Rate algorithm_base::IriBaseAlgorithm< Algorithm >::loop_rate_ [protected] |
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.
Definition at line 141 of file iri_base_algorithm.h.
ros::NodeHandle algorithm_base::IriBaseAlgorithm< Algorithm >::private_node_handle_ [protected] |
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.
Definition at line 131 of file iri_base_algorithm.h.
ros::NodeHandle algorithm_base::IriBaseAlgorithm< Algorithm >::public_node_handle_ [protected] |
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.
Definition at line 122 of file iri_base_algorithm.h.
boost::shared_ptr<boost::thread> algorithm_base::IriBaseAlgorithm< Algorithm >::ros_thread_ [private] |
ros spin thread
This boost thread object will manage the ros::spin function. It is instantiated and launched in the spin class method.
Definition at line 192 of file iri_base_algorithm.h.
pthread_t algorithm_base::IriBaseAlgorithm< Algorithm >::thread [protected] |
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.
Definition at line 104 of file iri_base_algorithm.h.