00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC. 00002 // Author 00003 // All rights reserved. 00004 // 00005 // This file is part of iri-ros-pkg 00006 // iri-ros-pkg is free software: you can redistribute it and/or modify 00007 // it under the terms of the GNU Lesser General Public License as published by 00008 // the Free Software Foundation, either version 3 of the License, or 00009 // at your option) any later version. 00010 // 00011 // This program is distributed in the hope that it will be useful, 00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 // GNU Lesser General Public License for more details. 00015 // 00016 // You should have received a copy of the GNU Lesser General Public License 00017 // along with this program. If not, see <http://www.gnu.org/licenses/>. 00018 // 00019 // IMPORTANT NOTE: This code has been generated through a script from the 00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness 00021 // of the scripts. ROS topics can be easly add by using those scripts. Please 00022 // refer to the IRI wiki page for more information: 00023 // http://wikiri.upc.es/index.php/Robotics_Lab 00024 00025 #ifndef _wam_driver_node_h_ 00026 #define _wam_driver_node_h_ 00027 00028 #include <iri_base_driver/iri_base_driver_node.h> 00029 #include "wam_driver.h" 00030 #include <Eigen/Dense> 00031 00032 // [publisher subscriber headers] 00033 #include <wam_msgs/RTJointPos.h> 00034 #include <trajectory_msgs/JointTrajectoryPoint.h> 00035 #include "sensor_msgs/JointState.h" 00036 #include "geometry_msgs/PoseStamped.h" 00037 00038 // [service client headers] 00039 #include "iri_wam_common_msgs/wamdriver.h" 00040 #include "iri_wam_common_msgs/joints_move.h" 00041 #include "iri_wam_common_msgs/pose_move.h" 00042 00043 // [action server client headers] 00044 #include <iri_wam_common_msgs/DMPTrackerAction.h> 00045 #include <iri_wam_common_msgs/LWPRTrajectoryReturningForceEstimationAction.h> 00046 #include <iri_action_server/iri_action_server.h> 00047 00048 // [action server msgs] 00049 #include <control_msgs/FollowJointTrajectoryAction.h> 00050 #include <actionlib/server/action_server.h> 00051 00052 #define HOLDON 0 00053 #define HOLDOFF 1 00054 00073 class WamDriverNode : public iri_base_driver::IriBaseNodeDriver<WamDriver> 00074 { 00075 //JointTrajectoryAction(Diamondback & Electric) 00076 typedef actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> ActionExecutor; 00077 typedef ActionExecutor::GoalHandle GoalHandle; 00078 //FollowJoinTrajectoryAction(Electric) 00079 typedef actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> ActionExecutorFollow; 00080 typedef ActionExecutorFollow::GoalHandle GoalHandleFollow; 00081 00082 private: 00083 // [publisher attributes] 00084 ros::Publisher joint_states_publisher; 00085 sensor_msgs::JointState JointState_msg; 00086 ros::Publisher pose_publisher; 00087 geometry_msgs::PoseStamped PoseStamped_msg; 00088 00089 // [subscriber attributes] 00090 ros::Subscriber jnt_pos_cmd_subscriber_; 00091 void jnt_pos_cmd_callback(const wam_msgs::RTJointPos::ConstPtr& msg); 00092 CMutex jnt_pos_cmd_mutex_; 00093 ros::Subscriber DMPTrackerNewGoal_subscriber_; 00094 void DMPTrackerNewGoal_callback(const trajectory_msgs::JointTrajectoryPoint::ConstPtr& msg); 00095 CMutex DMPTrackerNewGoal_mutex_; 00096 00097 // [service attributes] 00098 ros::ServiceServer wam_services_server_; 00099 bool wam_servicesCallback(iri_wam_common_msgs::wamdriver::Request & req, 00100 iri_wam_common_msgs::wamdriver::Response & res); 00101 00102 ros::ServiceServer joints_move_server; 00103 bool joints_moveCallback(iri_wam_common_msgs::joints_move::Request & req, 00104 iri_wam_common_msgs::joints_move::Response & res); 00105 00106 ros::ServiceServer pose_move_server; 00107 bool pose_moveCallback(iri_wam_common_msgs::pose_move::Request & req, 00108 iri_wam_common_msgs::pose_move::Response & res); 00109 00110 // [client attributes] 00111 00112 // [action server attributes] 00113 IriActionServer<iri_wam_common_msgs::DMPTrackerAction> DMPTracker_aserver_; 00114 void DMPTrackerStartCallback(const iri_wam_common_msgs::DMPTrackerGoalConstPtr& goal); 00115 void DMPTrackerStopCallback(void); 00116 bool DMPTrackerIsFinishedCallback(void); 00117 bool DMPTrackerHasSucceedCallback(void); 00118 void DMPTrackerGetResultCallback(iri_wam_common_msgs::DMPTrackerResultPtr& result); 00119 void DMPTrackerGetFeedbackCallback(iri_wam_common_msgs::DMPTrackerFeedbackPtr& feedback); 00120 IriActionServer<iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationAction> lwpr_trajectory_server_aserver_; 00121 void lwpr_trajectory_serverStartCallback(const iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationGoalConstPtr& goal); 00122 void lwpr_trajectory_serverStopCallback(void); 00123 bool lwpr_trajectory_serverIsFinishedCallback(void); 00124 bool lwpr_trajectory_serverHasSucceedCallback(void); 00125 void lwpr_trajectory_serverGetResultCallback(iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationResultPtr& result); 00126 void lwpr_trajectory_serverGetFeedbackCallback(iri_wam_common_msgs::LWPRTrajectoryReturningForceEstimationFeedbackPtr& feedback); 00127 00128 IriActionServer<control_msgs::FollowJointTrajectoryAction> follow_joint_trajectory_server_; 00129 void joint_trajectoryStartCallback(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal); 00130 void joint_trajectoryStopCallback(void); 00131 bool joint_trajectoryIsFinishedCallback(void); 00132 bool joint_trajectoryHasSucceedCallback(void); 00133 void joint_trajectoryGetResultCallback(control_msgs::FollowJointTrajectoryResultPtr& result); 00134 void joint_trajectoryGetFeedbackCallback(control_msgs::FollowJointTrajectoryFeedbackPtr& feedback); 00135 00136 void goalCB(GoalHandle gh); 00137 void cancelCB(GoalHandle gh); 00138 00139 void goalFollowCB(GoalHandleFollow gh); 00140 void canceFollowlCB(GoalHandleFollow gh); 00141 // [action client attributes] 00142 00150 void postNodeOpenHook(void); 00151 00152 void trajectory2follow(trajectory_msgs::JointTrajectory traj, bool& state); 00153 00154 public: 00172 WamDriverNode(ros::NodeHandle& nh); 00173 00180 ~WamDriverNode(); 00181 00182 protected: 00195 void mainNodeThread(void); 00196 00197 // [diagnostic functions] 00198 00209 void addNodeDiagnostics(void); 00210 00211 // [driver test functions] 00212 00222 void addNodeOpenedTests(void); 00223 00233 void addNodeStoppedTests(void); 00234 00244 void addNodeRunningTests(void); 00245 00253 void reconfigureNodeHook(int level); 00254 00255 }; 00256 00257 #endif