IRI ROS Base Node Class. More...
#include <iri_base_driver_node.h>
Public Member Functions | |
void | addDiagnostics (void) |
main node add diagnostics | |
void | addOpenedTests (void) |
open status driver main node tests | |
void | addRunningTests (void) |
run status driver main node tests | |
void | addStoppedTests (void) |
stop status driver main node tests | |
IriBaseNodeDriver (ros::NodeHandle &nh) | |
constructor | |
void | reconfigureHook (int level) |
main node dynamic reconfigure | |
~IriBaseNodeDriver () | |
destructor | |
Protected Member Functions | |
virtual void | addNodeDiagnostics (void)=0 |
node add diagnostics | |
virtual void | addNodeOpenedTests (void)=0 |
open status driver specific node tests | |
virtual void | addNodeRunningTests (void)=0 |
run status driver specific node tests | |
virtual void | addNodeStoppedTests (void)=0 |
stop status driver specific node tests | |
virtual void | mainNodeThread (void)=0 |
specific node thread | |
virtual void | postNodeOpenHook (void)=0 |
node implementation post open hook | |
void | postOpenHook (void) |
main node post open hook | |
void | preCloseHook (void) |
main node pre close hook | |
virtual void | preNodeCloseHook (void) |
node implementation pre close hook | |
virtual void | reconfigureNodeHook (int level)=0 |
specific node dynamic reconfigure | |
Static Protected Member Functions | |
static void * | mainThread (void *param) |
main node thread | |
Protected Attributes | |
ros::Rate | loop_rate_ |
main thread loop rate | |
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 |
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 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.
A shared library is generated together with IriBaseDriver class to force implementation of virtual methods to final user. Functions from ROS driver base class to perform tests, add diagnostics or hooks, are mainteined to implement common purpose behaviours and forwarded to the final user node class for specification.
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.
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.
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.
Definition at line 61 of file iri_base_driver_node.h.
iri_base_driver::IriBaseNodeDriver< Driver >::IriBaseNodeDriver | ( | ros::NodeHandle & | nh | ) |
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.
nh | a reference to the node handle object to manage all ROS topics. |
Definition at line 255 of file iri_base_driver_node.h.
iri_base_driver::IriBaseNodeDriver< Driver >::~IriBaseNodeDriver | ( | ) |
destructor
This destructor closes the driver object and kills the main thread.
Definition at line 352 of file iri_base_driver_node.h.
void iri_base_driver::IriBaseNodeDriver< Driver >::addDiagnostics | ( | void | ) | [virtual] |
main node add diagnostics
In this function ROS diagnostics applied to all node may be added.
Implements driver_base::DriverNode< Driver >.
Definition at line 317 of file iri_base_driver_node.h.
virtual void iri_base_driver::IriBaseNodeDriver< Driver >::addNodeDiagnostics | ( | void | ) | [protected, pure virtual] |
node add diagnostics
In this abstract function additional ROS diagnostics applied to the specific node may be added.
virtual void iri_base_driver::IriBaseNodeDriver< Driver >::addNodeOpenedTests | ( | void | ) | [protected, pure virtual] |
open status driver specific node tests
In this abstract function tests checking driver's functionallity in driver_base status=open can be added.
virtual void iri_base_driver::IriBaseNodeDriver< Driver >::addNodeRunningTests | ( | void | ) | [protected, pure virtual] |
run status driver specific node tests
In this abstract function tests checking driver's functionallity in driver_base status=run can be added.
virtual void iri_base_driver::IriBaseNodeDriver< Driver >::addNodeStoppedTests | ( | void | ) | [protected, pure virtual] |
stop status driver specific node tests
In this abstract function tests checking driver's functionallity in driver_base status=stop can be added.
void iri_base_driver::IriBaseNodeDriver< Driver >::addOpenedTests | ( | void | ) | [virtual] |
open status driver main node tests
In this function tests checking driver's functionallity in driver_base status=open can be added.
Implements driver_base::DriverNode< Driver >.
Definition at line 324 of file iri_base_driver_node.h.
void iri_base_driver::IriBaseNodeDriver< Driver >::addRunningTests | ( | void | ) | [virtual] |
run status driver main node tests
In this function tests checking driver's functionallity in driver_base status=run can be added.
Implements driver_base::DriverNode< Driver >.
Definition at line 338 of file iri_base_driver_node.h.
void iri_base_driver::IriBaseNodeDriver< Driver >::addStoppedTests | ( | void | ) | [virtual] |
stop status driver main node tests
In this function tests checking driver's functionallity in driver_base status=stop can be added.
Implements driver_base::DriverNode< Driver >.
Definition at line 331 of file iri_base_driver_node.h.
virtual void iri_base_driver::IriBaseNodeDriver< Driver >::mainNodeThread | ( | void | ) | [protected, pure virtual] |
specific node thread
In this abstract function specific commands for the driver base node have to be detailed.
void * iri_base_driver::IriBaseNodeDriver< Driver >::mainThread | ( | void * | param | ) | [static, protected] |
main node thread
This is the main thread node function. Code written here will be executed in every inherit driver node object. The loop won't exit until driver 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 IriBaseDriver object class. It is used to access to the object attributes and methods. |
Definition at line 271 of file iri_base_driver_node.h.
virtual void iri_base_driver::IriBaseNodeDriver< Driver >::postNodeOpenHook | ( | void | ) | [protected, pure virtual] |
node implementation post open hook
Abstrac function called by postOpenHook() that adds the specific driver node parameters to the dynamic reconfigure application.
void iri_base_driver::IriBaseNodeDriver< Driver >::postOpenHook | ( | void | ) | [protected] |
main node post open hook
This function sets the common parameters for all drivers which might be tuned for the ROS dynamic reconfigure application.
Definition at line 294 of file iri_base_driver_node.h.
void iri_base_driver::IriBaseNodeDriver< Driver >::preCloseHook | ( | void | ) | [protected] |
main node pre close hook
Definition at line 305 of file iri_base_driver_node.h.
void iri_base_driver::IriBaseNodeDriver< Driver >::preNodeCloseHook | ( | void | ) | [protected, virtual] |
node implementation pre close hook
Definition at line 312 of file iri_base_driver_node.h.
void iri_base_driver::IriBaseNodeDriver< Driver >::reconfigureHook | ( | int | level | ) | [virtual] |
main node dynamic reconfigure
level | integer |
Implements driver_base::DriverNode< Driver >.
Definition at line 345 of file iri_base_driver_node.h.
virtual void iri_base_driver::IriBaseNodeDriver< Driver >::reconfigureNodeHook | ( | int | level | ) | [protected, pure virtual] |
specific node dynamic reconfigure
This function is called reconfigureHook()
level | integer |
const unsigned int iri_base_driver::IriBaseNodeDriver< Driver >::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 127 of file iri_base_driver_node.h.
ros::Rate iri_base_driver::IriBaseNodeDriver< Driver >::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 119 of file iri_base_driver_node.h.
ros::NodeHandle iri_base_driver::IriBaseNodeDriver< Driver >::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 109 of file iri_base_driver_node.h.
pthread_t iri_base_driver::IriBaseNodeDriver< Driver >::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 72 of file iri_base_driver_node.h.