Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Private Attributes
WamDriverNode Class Reference

IRI ROS Specific Driver Class. More...

#include <wam_driver_node.h>

Inheritance diagram for WamDriverNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 WamDriverNode (ros::NodeHandle &nh)
 constructor
 ~WamDriverNode ()
 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 Types

typedef
actionlib::ActionServer
< control_msgs::FollowJointTrajectoryAction
ActionExecutor
typedef
actionlib::ActionServer
< control_msgs::FollowJointTrajectoryAction
ActionExecutorFollow
typedef ActionExecutor::GoalHandle GoalHandle
typedef
ActionExecutorFollow::GoalHandle 
GoalHandleFollow

Private Member Functions

void canceFollowlCB (GoalHandleFollow gh)
void cancelCB (GoalHandle gh)
void DMPTrackerGetFeedbackCallback (iri_wam_common_msgs::DMPTrackerFeedbackPtr &feedback)
void DMPTrackerGetResultCallback (iri_wam_common_msgs::DMPTrackerResultPtr &result)
bool DMPTrackerHasSucceedCallback (void)
bool DMPTrackerIsFinishedCallback (void)
void DMPTrackerNewGoal_callback (const trajectory_msgs::JointTrajectoryPoint::ConstPtr &msg)
void DMPTrackerStartCallback (const iri_wam_common_msgs::DMPTrackerGoalConstPtr &goal)
void DMPTrackerStopCallback (void)
void goalCB (GoalHandle gh)
void goalFollowCB (GoalHandleFollow gh)
void jnt_pos_cmd_callback (const wam_msgs::RTJointPos::ConstPtr &msg)
void joint_trajectoryGetFeedbackCallback (control_msgs::FollowJointTrajectoryFeedbackPtr &feedback)
void joint_trajectoryGetResultCallback (control_msgs::FollowJointTrajectoryResultPtr &result)
bool joint_trajectoryHasSucceedCallback (void)
bool joint_trajectoryIsFinishedCallback (void)
void joint_trajectoryStartCallback (const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
void joint_trajectoryStopCallback (void)
bool joints_moveCallback (iri_wam_common_msgs::joints_move::Request &req, iri_wam_common_msgs::joints_move::Response &res)
void lwpr_trajectory_serverGetFeedbackCallback (iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationFeedbackPtr &feedback)
void lwpr_trajectory_serverGetResultCallback (iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationResultPtr &result)
bool lwpr_trajectory_serverHasSucceedCallback (void)
bool lwpr_trajectory_serverIsFinishedCallback (void)
void lwpr_trajectory_serverStartCallback (const iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationGoalConstPtr &goal)
void lwpr_trajectory_serverStopCallback (void)
bool pose_moveCallback (iri_wam_common_msgs::pose_move::Request &req, iri_wam_common_msgs::pose_move::Response &res)
void postNodeOpenHook (void)
 post open hook
void trajectory2follow (trajectory_msgs::JointTrajectory traj, bool &state)
bool wam_servicesCallback (iri_wam_common_msgs::wamdriver::Request &req, iri_wam_common_msgs::wamdriver::Response &res)

Private Attributes

IriActionServer
< iri_wam_common_msgs::DMPTrackerAction > 
DMPTracker_aserver_
CMutex DMPTrackerNewGoal_mutex_
ros::Subscriber DMPTrackerNewGoal_subscriber_
IriActionServer
< control_msgs::FollowJointTrajectoryAction
follow_joint_trajectory_server_
CMutex jnt_pos_cmd_mutex_
ros::Subscriber jnt_pos_cmd_subscriber_
ros::Publisher joint_states_publisher
ros::ServiceServer joints_move_server
sensor_msgs::JointState JointState_msg
IriActionServer
< iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationAction > 
lwpr_trajectory_server_aserver_
ros::ServiceServer pose_move_server
ros::Publisher pose_publisher
geometry_msgs::PoseStamped PoseStamped_msg
ros::ServiceServer wam_services_server_

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 73 of file wam_driver_node.h.


Member Typedef Documentation

Definition at line 76 of file wam_driver_node.h.

Definition at line 79 of file wam_driver_node.h.

Definition at line 77 of file wam_driver_node.h.

Definition at line 80 of file wam_driver_node.h.


Constructor & Destructor Documentation

constructor

This constructor mainly creates and initializes the WamDriverNode 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 wam_driver_node.cpp.

Destructor.

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

Definition at line 491 of file wam_driver_node.cpp.


Member Function Documentation

void WamDriverNode::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< WamDriver >.

Definition at line 471 of file wam_driver_node.cpp.

void WamDriverNode::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< WamDriver >.

Definition at line 475 of file wam_driver_node.cpp.

void WamDriverNode::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< WamDriver >.

Definition at line 483 of file wam_driver_node.cpp.

void WamDriverNode::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< WamDriver >.

Definition at line 479 of file wam_driver_node.cpp.

void WamDriverNode::cancelCB ( GoalHandle  gh) [private]
void WamDriverNode::DMPTrackerGetFeedbackCallback ( iri_wam_common_msgs::DMPTrackerFeedbackPtr &  feedback) [private]

Definition at line 288 of file wam_driver_node.cpp.

void WamDriverNode::DMPTrackerGetResultCallback ( iri_wam_common_msgs::DMPTrackerResultPtr &  result) [private]

Definition at line 280 of file wam_driver_node.cpp.

Definition at line 268 of file wam_driver_node.cpp.

Definition at line 256 of file wam_driver_node.cpp.

void WamDriverNode::DMPTrackerNewGoal_callback ( const trajectory_msgs::JointTrajectoryPoint::ConstPtr &  msg) [private]

Definition at line 138 of file wam_driver_node.cpp.

void WamDriverNode::DMPTrackerStartCallback ( const iri_wam_common_msgs::DMPTrackerGoalConstPtr &  goal) [private]

Definition at line 240 of file wam_driver_node.cpp.

void WamDriverNode::DMPTrackerStopCallback ( void  ) [private]

Definition at line 249 of file wam_driver_node.cpp.

void WamDriverNode::goalCB ( GoalHandle  gh) [private]

Definition at line 424 of file wam_driver_node.cpp.

Definition at line 433 of file wam_driver_node.cpp.

void WamDriverNode::jnt_pos_cmd_callback ( const wam_msgs::RTJointPos::ConstPtr &  msg) [private]

Definition at line 123 of file wam_driver_node.cpp.

Definition at line 415 of file wam_driver_node.cpp.

Definition at line 403 of file wam_driver_node.cpp.

Definition at line 387 of file wam_driver_node.cpp.

Definition at line 369 of file wam_driver_node.cpp.

Definition at line 348 of file wam_driver_node.cpp.

Definition at line 359 of file wam_driver_node.cpp.

bool WamDriverNode::joints_moveCallback ( iri_wam_common_msgs::joints_move::Request &  req,
iri_wam_common_msgs::joints_move::Response &  res 
) [private]

Definition at line 183 of file wam_driver_node.cpp.

void WamDriverNode::lwpr_trajectory_serverGetFeedbackCallback ( iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationFeedbackPtr &  feedback) [private]

Definition at line 339 of file wam_driver_node.cpp.

void WamDriverNode::lwpr_trajectory_serverGetResultCallback ( iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationResultPtr &  result) [private]

Definition at line 332 of file wam_driver_node.cpp.

Definition at line 321 of file wam_driver_node.cpp.

Definition at line 309 of file wam_driver_node.cpp.

void WamDriverNode::lwpr_trajectory_serverStartCallback ( const iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationGoalConstPtr &  goal) [private]

Definition at line 295 of file wam_driver_node.cpp.

Definition at line 302 of file wam_driver_node.cpp.

void WamDriverNode::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 my 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< WamDriver >.

Definition at line 65 of file wam_driver_node.cpp.

bool WamDriverNode::pose_moveCallback ( iri_wam_common_msgs::pose_move::Request &  req,
iri_wam_common_msgs::pose_move::Response &  res 
) [private]

Definition at line 210 of file wam_driver_node.cpp.

void WamDriverNode::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< WamDriver >.

Definition at line 467 of file wam_driver_node.cpp.

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

specific node dynamic reconfigure

This function is called reconfigureHook()

Parameters:
levelinteger

Implements iri_base_driver::IriBaseNodeDriver< WamDriver >.

Definition at line 487 of file wam_driver_node.cpp.

void WamDriverNode::trajectory2follow ( trajectory_msgs::JointTrajectory  traj,
bool state 
) [private]

Definition at line 442 of file wam_driver_node.cpp.

bool WamDriverNode::wam_servicesCallback ( iri_wam_common_msgs::wamdriver::Request &  req,
iri_wam_common_msgs::wamdriver::Response &  res 
) [private]

Definition at line 154 of file wam_driver_node.cpp.


Member Data Documentation

IriActionServer<iri_wam_common_msgs::DMPTrackerAction> WamDriverNode::DMPTracker_aserver_ [private]

Definition at line 113 of file wam_driver_node.h.

Definition at line 95 of file wam_driver_node.h.

Definition at line 93 of file wam_driver_node.h.

Definition at line 128 of file wam_driver_node.h.

Definition at line 92 of file wam_driver_node.h.

Definition at line 90 of file wam_driver_node.h.

Definition at line 84 of file wam_driver_node.h.

Definition at line 102 of file wam_driver_node.h.

sensor_msgs::JointState WamDriverNode::JointState_msg [private]

Definition at line 85 of file wam_driver_node.h.

IriActionServer<iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationAction> WamDriverNode::lwpr_trajectory_server_aserver_ [private]

Definition at line 120 of file wam_driver_node.h.

Definition at line 106 of file wam_driver_node.h.

Definition at line 86 of file wam_driver_node.h.

geometry_msgs::PoseStamped WamDriverNode::PoseStamped_msg [private]

Definition at line 87 of file wam_driver_node.h.

Definition at line 98 of file wam_driver_node.h.


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


iri_wam_wrapper
Author(s): Pol Monso
autogenerated on Fri Dec 6 2013 21:47:20