Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
TibiDaboArmDriverNode Class Reference

IRI ROS Specific Driver Class. More...

#include <tibi_dabo_arm_driver_node.h>

Inheritance diagram for TibiDaboArmDriverNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 TibiDaboArmDriverNode (ros::NodeHandle &nh)
 constructor
 ~TibiDaboArmDriverNode (void)
 Destructor.

Protected Member Functions

void addNodeDiagnostics (void)
 node add diagnostics
void addNodeOpenedTests (void)
 open status driver tests
void addNodeRunningTests (void)
 run status driver tests
void addNodeStoppedTests (void)
 stop status driver tests
void check_motion_sequence_status (diagnostic_updater::DiagnosticStatusWrapper &stat)
void mainNodeThread (void)
 main node thread
void reconfigureNodeHook (int level)
 specific node dynamic reconfigure

Private Member Functions

void joint_motion_getFeedbackCallback (control_msgs::FollowJointTrajectoryFeedbackPtr &feedback)
void joint_motion_getResultCallback (control_msgs::FollowJointTrajectoryResultPtr &result)
bool joint_motion_hasSucceedCallback (void)
bool joint_motion_isFinishedCallback (void)
void joint_motion_startCallback (const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
void joint_motion_stopCallback (void)
void motion_sequence_getFeedbackCallback (tibi_dabo_msgs::sequenceFeedbackPtr &feedback)
void motion_sequence_getResultCallback (tibi_dabo_msgs::sequenceResultPtr &result)
bool motion_sequence_hasSucceedCallback (void)
bool motion_sequence_isFinishedCallback (void)
void motion_sequence_startCallback (const tibi_dabo_msgs::sequenceGoalConstPtr &goal)
void motion_sequence_stopCallback (void)
void postNodeOpenHook (void)
 post open hook
void preNodeCloseHook (void)

Private Attributes

ros::Publisher joint_feedback_publisher_
IriActionServer
< control_msgs::FollowJointTrajectoryAction
joint_motion_aserver_
sensor_msgs::JointState JointState_msg_
IriActionServer
< tibi_dabo_msgs::sequenceAction
motion_sequence_aserver_
std::string robot_id
std::string side_id

Detailed Description

IRI ROS Specific Driver Class.

This class inherits from the IRI Core class IriBaseNodeDriver<IriBaseDriver>, to provide an execution thread to the driver object. A complete framework with utilites to test the node functionallity or to add diagnostics to specific situations is also given. The inherit template design form allows complete access to any IriBaseDriver object implementation.

As mentioned, tests in the different driver states can be performed through class methods such as addNodeOpenedTests() or addNodeRunningTests(). Tests common to all nodes may be also executed in the pattern class IriBaseNodeDriver. Similarly to the tests, diagnostics can easyly be added. See ROS Wiki for more details: http://www.ros.org/wiki/diagnostics/ (Tutorials: Creating a Diagnostic Analyzer) http://www.ros.org/wiki/self_test/ (Example: Self Test)

Definition at line 62 of file tibi_dabo_arm_driver_node.h.


Constructor & Destructor Documentation

constructor

This constructor mainly creates and initializes the TibiDaboArmDriverNode topics through the given public_node_handle object. IriBaseNodeDriver attributes may be also modified to suit node specifications.

All kind of ROS topics (publishers, subscribers, servers or clients) can be easyly generated with the scripts in the iri_ros_scripts package. Refer to ROS and IRI Wiki pages for more details:

http://www.ros.org/wiki/ROS/Tutorials/WritingPublisherSubscriber(c++) http://www.ros.org/wiki/ROS/Tutorials/WritingServiceClient(c++) http://wikiri.upc.es/index.php/Robotics_Lab

Parameters:
nha reference to the node handle object to manage all ROS topics.

Definition at line 5 of file tibi_dabo_arm_driver_node.cpp.

Destructor.

This destructor is called when the object is about to be destroyed.

Definition at line 575 of file tibi_dabo_arm_driver_node.cpp.


Member Function Documentation

void TibiDaboArmDriverNode::addNodeDiagnostics ( void  ) [protected, virtual]

node add diagnostics

In this function ROS diagnostics applied to this specific node may be added. Common use diagnostics for all nodes are already called from IriBaseNodeDriver::addDiagnostics(), which also calls this function. Information of how ROS diagnostics work can be readen here: http://www.ros.org/wiki/diagnostics/ http://www.ros.org/doc/api/diagnostic_updater/html/example_8cpp-source.html

Implements iri_base_driver::IriBaseNodeDriver< TibiDaboArmDriver >.

Definition at line 554 of file tibi_dabo_arm_driver_node.cpp.

void TibiDaboArmDriverNode::addNodeOpenedTests ( void  ) [protected, virtual]

open status driver tests

In this function tests checking driver's functionallity when driver_base status=open can be added. Common use tests for all nodes are already called from IriBaseNodeDriver tests methods. For more details on how ROS tests work, please refer to the Self Test example in: http://www.ros.org/wiki/self_test/

Implements iri_base_driver::IriBaseNodeDriver< TibiDaboArmDriver >.

Definition at line 559 of file tibi_dabo_arm_driver_node.cpp.

void TibiDaboArmDriverNode::addNodeRunningTests ( void  ) [protected, virtual]

run status driver tests

In this function tests checking driver's functionallity when driver_base status=run can be added. Common use tests for all nodes are already called from IriBaseNodeDriver tests methods. For more details on how ROS tests work, please refer to the Self Test example in: http://www.ros.org/wiki/self_test/

Implements iri_base_driver::IriBaseNodeDriver< TibiDaboArmDriver >.

Definition at line 567 of file tibi_dabo_arm_driver_node.cpp.

void TibiDaboArmDriverNode::addNodeStoppedTests ( void  ) [protected, virtual]

stop status driver tests

In this function tests checking driver's functionallity when driver_base status=stop can be added. Common use tests for all nodes are already called from IriBaseNodeDriver tests methods. For more details on how ROS tests work, please refer to the Self Test example in: http://www.ros.org/wiki/self_test/

Implements iri_base_driver::IriBaseNodeDriver< TibiDaboArmDriver >.

Definition at line 563 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 124 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 502 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 483 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 464 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 445 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 288 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 427 of file tibi_dabo_arm_driver_node.cpp.

void TibiDaboArmDriverNode::mainNodeThread ( void  ) [protected, virtual]

main node thread

This is the main thread node function. Code written here will be executed in every node loop while the driver is on running state. Loop frequency can be tuned by modifying loop_rate attribute.

Here data related to the process loop or to ROS topics (mainly data structs related to the MSG and SRV files) must be updated. ROS publisher objects must publish their data in this process. ROS client servers may also request data to the corresponding server topics.

Implements iri_base_driver::IriBaseNodeDriver< TibiDaboArmDriver >.

Definition at line 63 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 268 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 249 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 230 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 211 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 157 of file tibi_dabo_arm_driver_node.cpp.

Definition at line 192 of file tibi_dabo_arm_driver_node.cpp.

void TibiDaboArmDriverNode::postNodeOpenHook ( void  ) [private, virtual]

post open hook

This function is called by IriBaseNodeDriver::postOpenHook(). In this function specific parameters from the driver must be added so the ROS dynamic reconfigure application can update them.

Implements iri_base_driver::IriBaseNodeDriver< TibiDaboArmDriver >.

Definition at line 532 of file tibi_dabo_arm_driver_node.cpp.

void TibiDaboArmDriverNode::preNodeCloseHook ( void  ) [private, virtual]
void TibiDaboArmDriverNode::reconfigureNodeHook ( int  level) [protected, virtual]

specific node dynamic reconfigure

This function is called reconfigureHook()

Parameters:
levelinteger

Implements iri_base_driver::IriBaseNodeDriver< TibiDaboArmDriver >.

Definition at line 571 of file tibi_dabo_arm_driver_node.cpp.


Member Data Documentation

Definition at line 66 of file tibi_dabo_arm_driver_node.h.

Definition at line 88 of file tibi_dabo_arm_driver_node.h.

sensor_msgs::JointState TibiDaboArmDriverNode::JointState_msg_ [private]

Definition at line 67 of file tibi_dabo_arm_driver_node.h.

Definition at line 80 of file tibi_dabo_arm_driver_node.h.

std::string TibiDaboArmDriverNode::robot_id [private]

Definition at line 69 of file tibi_dabo_arm_driver_node.h.

std::string TibiDaboArmDriverNode::side_id [private]

Definition at line 70 of file tibi_dabo_arm_driver_node.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


tibi_dabo_arm_node
Author(s): Sergi Hernandez Juan
autogenerated on Fri Sep 27 2013 10:24:22