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 _tibi_arm_node_driver_node_h_ 00026 #define _tibi_arm_node_driver_node_h_ 00027 00028 #include <iri_base_driver/iri_base_driver_node.h> 00029 #include "tibi_arm_node_driver.h" 00030 00031 // [publisher subscriber headers] 00032 #include <sensor_msgs/JointState.h> 00033 00034 // [service client headers] 00035 00036 // [action server client headers] 00037 #include <control_msgs/FollowJointTrajectoryAction.h> 00038 #include <iri_action_server/iri_action_server.h> 00039 #include <tibi_dabo_msgs/sequenceAction.h> 00040 00041 // diagnostic headers 00042 #include "diagnostic_updater/diagnostic_updater.h" 00043 #include "diagnostic_updater/publisher.h" 00044 00062 class TibiArmNodeDriverNode : public iri_base_driver::IriBaseNodeDriver<TibiArmNodeDriver> 00063 { 00064 private: 00065 std::string side_id; 00066 00067 // [publisher attributes] 00068 ros::Publisher joint_feedback_publisher_; 00069 sensor_msgs::JointState JointState_msg_; 00070 00071 // [subscriber attributes] 00072 00073 // [service attributes] 00074 00075 // [client attributes] 00076 00077 // [action server attributes] 00078 IriActionServer<control_msgs::FollowJointTrajectoryAction> joint_motion_aserver_; 00079 void joint_motionStartCallback(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal); 00080 void joint_motionStopCallback(void); 00081 bool joint_motionIsFinishedCallback(void); 00082 bool joint_motionHasSucceedCallback(void); 00083 void joint_motionGetResultCallback(control_msgs::FollowJointTrajectoryResultPtr& result); 00084 void joint_motionGetFeedbackCallback(control_msgs::FollowJointTrajectoryFeedbackPtr& feedback); 00085 IriActionServer<tibi_dabo_msgs::sequenceAction> motion_sequence_aserver_; 00086 void motion_sequenceStartCallback(const tibi_dabo_msgs::sequenceGoalConstPtr& goal); 00087 void motion_sequenceStopCallback(void); 00088 bool motion_sequenceIsFinishedCallback(void); 00089 bool motion_sequenceHasSucceedCallback(void); 00090 void motion_sequenceGetResultCallback(tibi_dabo_msgs::sequenceResultPtr& result); 00091 void motion_sequenceGetFeedbackCallback(tibi_dabo_msgs::sequenceFeedbackPtr& feedback); 00092 00093 // [action client attributes] 00094 00102 void postNodeOpenHook(void); 00103 void preNodeCloseHook(void); 00104 00105 public: 00123 TibiArmNodeDriverNode(ros::NodeHandle& nh); 00124 00131 ~TibiArmNodeDriverNode(void); 00132 00133 protected: 00146 void mainNodeThread(void); 00147 00148 // [diagnostic functions] 00149 void check_motion_sequence_status(diagnostic_updater::DiagnosticStatusWrapper &stat); 00150 00161 void addNodeDiagnostics(void); 00162 00163 // [driver test functions] 00164 00174 void addNodeOpenedTests(void); 00175 00185 void addNodeStoppedTests(void); 00186 00196 void addNodeRunningTests(void); 00197 00205 void reconfigureNodeHook(int level); 00206 00207 }; 00208 00209 #endif