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

IRI ROS Specific Driver Class. More...

#include <darwin_robot_driver_node.h>

Inheritance diagram for DarwinRobotDriverNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 DarwinRobotDriverNode (ros::NodeHandle &nh)
 constructor
 ~DarwinRobotDriverNode (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 mainNodeThread (void)
 main node thread
void reconfigureNodeHook (int level)
 specific node dynamic reconfigure

Private Member Functions

void cmd_vel_callback (const geometry_msgs::Twist::ConstPtr &msg)
void execute_action_callback (const std_msgs::Int32::ConstPtr &msg)
void head_target_callback (const std_msgs::Float64MultiArray::ConstPtr &msg)
void move_jointsGetFeedbackCallback (control_msgs::FollowJointTrajectoryFeedbackPtr &feedback)
void move_jointsGetResultCallback (control_msgs::FollowJointTrajectoryResultPtr &result)
bool move_jointsHasSucceedCallback (void)
bool move_jointsIsFinishedCallback (void)
void move_jointsStartCallback (const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
void move_jointsStopCallback (void)
void move_left_arm_jointsGetFeedbackCallback (control_msgs::FollowJointTrajectoryFeedbackPtr &feedback)
void move_left_arm_jointsGetResultCallback (control_msgs::FollowJointTrajectoryResultPtr &result)
bool move_left_arm_jointsHasSucceedCallback (void)
bool move_left_arm_jointsIsFinishedCallback (void)
void move_left_arm_jointsStartCallback (const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
void move_left_arm_jointsStopCallback (void)
void move_right_arm_jointsGetFeedbackCallback (control_msgs::FollowJointTrajectoryFeedbackPtr &feedback)
void move_right_arm_jointsGetResultCallback (control_msgs::FollowJointTrajectoryResultPtr &result)
bool move_right_arm_jointsHasSucceedCallback (void)
bool move_right_arm_jointsIsFinishedCallback (void)
void move_right_arm_jointsStartCallback (const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
void move_right_arm_jointsStopCallback (void)
void postNodeOpenHook (void)
 post open hook
void tracking_headGetFeedbackCallback (iri_darwin_robot::tracking_headFeedbackPtr &feedback)
void tracking_headGetResultCallback (iri_darwin_robot::tracking_headResultPtr &result)
bool tracking_headHasSucceedCallback (void)
bool tracking_headIsFinishedCallback (void)
void tracking_headStartCallback (const iri_darwin_robot::tracking_headGoalConstPtr &goal)
void tracking_headStopCallback (void)

Private Attributes

ros::Publisher adc_channels_publisher_
CMutex cmd_vel_mutex_
ros::Subscriber cmd_vel_subscriber_
CMutex execute_action_mutex_
ros::Subscriber execute_action_subscriber_
std_msgs::Float64MultiArray Float64MultiArray_msg_
std::string general_target_id
std_msgs::Float64MultiArray head_target_
CMutex head_target_mutex_
ros::Subscriber head_target_subscriber_
sensor_msgs::Imu Imu_msg_
ros::Publisher inertial_publisher_
ros::Publisher joint_states_publisher_
sensor_msgs::JointState JointState_msg_
std::string left_arm_target_id
IriActionServer
< control_msgs::FollowJointTrajectoryAction
move_joints_aserver_
IriActionServer
< control_msgs::FollowJointTrajectoryAction
move_left_arm_joints_aserver_
IriActionServer
< control_msgs::FollowJointTrajectoryAction
move_right_arm_joints_aserver_
std::string right_arm_target_id
IriActionServer
< iri_darwin_robot::tracking_headAction
tracking_head_aserver_

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 darwin_robot_driver_node.h.


Constructor & Destructor Documentation

constructor

This constructor mainly creates and initializes the DarwinNodeDriverNode 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 4 of file darwin_robot_driver_node.cpp.

Destructor.

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

Definition at line 647 of file darwin_robot_driver_node.cpp.


Member Function Documentation

void DarwinRobotDriverNode::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< DarwinRobotDriver >.

Definition at line 627 of file darwin_robot_driver_node.cpp.

void DarwinRobotDriverNode::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< DarwinRobotDriver >.

Definition at line 631 of file darwin_robot_driver_node.cpp.

void DarwinRobotDriverNode::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< DarwinRobotDriver >.

Definition at line 639 of file darwin_robot_driver_node.cpp.

void DarwinRobotDriverNode::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< DarwinRobotDriver >.

Definition at line 635 of file darwin_robot_driver_node.cpp.

void DarwinRobotDriverNode::cmd_vel_callback ( const geometry_msgs::Twist::ConstPtr &  msg) [private]

Definition at line 206 of file darwin_robot_driver_node.cpp.

void DarwinRobotDriverNode::execute_action_callback ( const std_msgs::Int32::ConstPtr &  msg) [private]

Definition at line 192 of file darwin_robot_driver_node.cpp.

void DarwinRobotDriverNode::head_target_callback ( const std_msgs::Float64MultiArray::ConstPtr &  msg) [private]

Definition at line 175 of file darwin_robot_driver_node.cpp.

void DarwinRobotDriverNode::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< DarwinRobotDriver >.

Definition at line 64 of file darwin_robot_driver_node.cpp.

Definition at line 614 of file darwin_robot_driver_node.cpp.

Definition at line 606 of file darwin_robot_driver_node.cpp.

Definition at line 594 of file darwin_robot_driver_node.cpp.

Definition at line 581 of file darwin_robot_driver_node.cpp.

Definition at line 495 of file darwin_robot_driver_node.cpp.

Definition at line 573 of file darwin_robot_driver_node.cpp.

Definition at line 488 of file darwin_robot_driver_node.cpp.

Definition at line 480 of file darwin_robot_driver_node.cpp.

Definition at line 468 of file darwin_robot_driver_node.cpp.

Definition at line 455 of file darwin_robot_driver_node.cpp.

Definition at line 410 of file darwin_robot_driver_node.cpp.

Definition at line 447 of file darwin_robot_driver_node.cpp.

Definition at line 403 of file darwin_robot_driver_node.cpp.

Definition at line 395 of file darwin_robot_driver_node.cpp.

Definition at line 383 of file darwin_robot_driver_node.cpp.

Definition at line 370 of file darwin_robot_driver_node.cpp.

Definition at line 325 of file darwin_robot_driver_node.cpp.

Definition at line 362 of file darwin_robot_driver_node.cpp.

void DarwinRobotDriverNode::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< DarwinRobotDriver >.

Definition at line 623 of file darwin_robot_driver_node.cpp.

void DarwinRobotDriverNode::reconfigureNodeHook ( int  level) [protected, virtual]

specific node dynamic reconfigure

This function is called reconfigureHook()

Parameters:
levelinteger

Implements iri_base_driver::IriBaseNodeDriver< DarwinRobotDriver >.

Definition at line 643 of file darwin_robot_driver_node.cpp.

Definition at line 314 of file darwin_robot_driver_node.cpp.

Definition at line 306 of file darwin_robot_driver_node.cpp.

Definition at line 294 of file darwin_robot_driver_node.cpp.

Definition at line 282 of file darwin_robot_driver_node.cpp.

Definition at line 250 of file darwin_robot_driver_node.cpp.

Definition at line 274 of file darwin_robot_driver_node.cpp.


Member Data Documentation

Definition at line 66 of file darwin_robot_driver_node.h.

Definition at line 83 of file darwin_robot_driver_node.h.

Definition at line 81 of file darwin_robot_driver_node.h.

Definition at line 80 of file darwin_robot_driver_node.h.

Definition at line 78 of file darwin_robot_driver_node.h.

std_msgs::Float64MultiArray DarwinRobotDriverNode::Float64MultiArray_msg_ [private]

Definition at line 67 of file darwin_robot_driver_node.h.

Definition at line 122 of file darwin_robot_driver_node.h.

std_msgs::Float64MultiArray DarwinRobotDriverNode::head_target_ [private]

Definition at line 77 of file darwin_robot_driver_node.h.

Definition at line 76 of file darwin_robot_driver_node.h.

Definition at line 74 of file darwin_robot_driver_node.h.

sensor_msgs::Imu DarwinRobotDriverNode::Imu_msg_ [private]

Definition at line 69 of file darwin_robot_driver_node.h.

Definition at line 68 of file darwin_robot_driver_node.h.

Definition at line 70 of file darwin_robot_driver_node.h.

sensor_msgs::JointState DarwinRobotDriverNode::JointState_msg_ [private]

Definition at line 71 of file darwin_robot_driver_node.h.

Definition at line 120 of file darwin_robot_driver_node.h.

Definition at line 111 of file darwin_robot_driver_node.h.

Definition at line 104 of file darwin_robot_driver_node.h.

Definition at line 97 of file darwin_robot_driver_node.h.

Definition at line 121 of file darwin_robot_driver_node.h.

Definition at line 90 of file darwin_robot_driver_node.h.


The documentation for this class was generated from the following files:


iri_darwin_robot
Author(s): shernand
autogenerated on Fri Dec 6 2013 20:53:54