darwin_robot_driver_node.h
Go to the documentation of this file.
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 _darwin_node_driver_node_h_
00026 #define _darwin_node_driver_node_h_
00027 
00028 #include <iri_base_driver/iri_base_driver_node.h>
00029 #include "darwin_robot_driver.h"
00030 
00031 // [publisher subscriber headers]
00032 #include <std_msgs/Float64MultiArray.h>
00033 #include <std_msgs/Int32.h>
00034 #include <sensor_msgs/Imu.h>
00035 #include <sensor_msgs/JointState.h>
00036 #include <geometry_msgs/Twist.h>
00037 
00038 // [service client headers]
00039 
00040 // [action server client headers]
00041 #include <iri_darwin_robot/tracking_headAction.h>
00042 #include <iri_action_server/iri_action_server.h>
00043 #include <control_msgs/FollowJointTrajectoryAction.h>
00044 
00062 class DarwinRobotDriverNode : public iri_base_driver::IriBaseNodeDriver<DarwinRobotDriver>
00063 {
00064   private:
00065     // [publisher attributes]
00066     ros::Publisher adc_channels_publisher_;
00067     std_msgs::Float64MultiArray Float64MultiArray_msg_;
00068     ros::Publisher inertial_publisher_;
00069     sensor_msgs::Imu Imu_msg_;
00070     ros::Publisher joint_states_publisher_;
00071     sensor_msgs::JointState JointState_msg_;
00072 
00073     // [subscriber attributes]
00074     ros::Subscriber head_target_subscriber_;
00075     void head_target_callback(const std_msgs::Float64MultiArray::ConstPtr& msg);
00076     CMutex head_target_mutex_;
00077     std_msgs::Float64MultiArray head_target_;
00078     ros::Subscriber execute_action_subscriber_;
00079     void execute_action_callback(const std_msgs::Int32::ConstPtr& msg);
00080     CMutex execute_action_mutex_;
00081     ros::Subscriber cmd_vel_subscriber_;
00082     void cmd_vel_callback(const geometry_msgs::Twist::ConstPtr& msg);
00083     CMutex cmd_vel_mutex_;
00084 
00085     // [service attributes]
00086  
00087     // [client attributes]
00088 
00089     // [action server attributes]
00090     IriActionServer<iri_darwin_robot::tracking_headAction> tracking_head_aserver_;
00091     void tracking_headStartCallback(const iri_darwin_robot::tracking_headGoalConstPtr& goal);
00092     void tracking_headStopCallback(void);
00093     bool tracking_headIsFinishedCallback(void);
00094     bool tracking_headHasSucceedCallback(void);
00095     void tracking_headGetResultCallback(iri_darwin_robot::tracking_headResultPtr& result);
00096     void tracking_headGetFeedbackCallback(iri_darwin_robot::tracking_headFeedbackPtr& feedback);
00097     IriActionServer<control_msgs::FollowJointTrajectoryAction> move_right_arm_joints_aserver_;
00098     void move_right_arm_jointsStartCallback(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal);
00099     void move_right_arm_jointsStopCallback(void);
00100     bool move_right_arm_jointsIsFinishedCallback(void);
00101     bool move_right_arm_jointsHasSucceedCallback(void);
00102     void move_right_arm_jointsGetResultCallback(control_msgs::FollowJointTrajectoryResultPtr& result);
00103     void move_right_arm_jointsGetFeedbackCallback(control_msgs::FollowJointTrajectoryFeedbackPtr& feedback);
00104     IriActionServer<control_msgs::FollowJointTrajectoryAction> move_left_arm_joints_aserver_;
00105     void move_left_arm_jointsStartCallback(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal);
00106     void move_left_arm_jointsStopCallback(void);
00107     bool move_left_arm_jointsIsFinishedCallback(void);
00108     bool move_left_arm_jointsHasSucceedCallback(void);
00109     void move_left_arm_jointsGetResultCallback(control_msgs::FollowJointTrajectoryResultPtr& result);
00110     void move_left_arm_jointsGetFeedbackCallback(control_msgs::FollowJointTrajectoryFeedbackPtr& feedback);
00111     IriActionServer<control_msgs::FollowJointTrajectoryAction> move_joints_aserver_;
00112     void move_jointsStartCallback(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal);
00113     void move_jointsStopCallback(void);
00114     bool move_jointsIsFinishedCallback(void);
00115     bool move_jointsHasSucceedCallback(void);
00116     void move_jointsGetResultCallback(control_msgs::FollowJointTrajectoryResultPtr& result);
00117     void move_jointsGetFeedbackCallback(control_msgs::FollowJointTrajectoryFeedbackPtr& feedback);
00118     
00119     // joint motion event identifiers
00120     std::string left_arm_target_id;
00121     std::string right_arm_target_id;
00122     std::string general_target_id;
00123 
00124     // [action client attributes]
00125 
00133     void postNodeOpenHook(void);
00134 
00135   public:
00153     DarwinRobotDriverNode(ros::NodeHandle& nh);
00154 
00161     ~DarwinRobotDriverNode(void);
00162 
00163   protected:
00176     void mainNodeThread(void);
00177 
00178     // [diagnostic functions]
00179 
00190     void addNodeDiagnostics(void);
00191 
00192     // [driver test functions]
00193 
00203     void addNodeOpenedTests(void);
00204 
00214     void addNodeStoppedTests(void);
00215 
00225     void addNodeRunningTests(void);
00226 
00234     void reconfigureNodeHook(int level);
00235 
00236 };
00237 
00238 #endif


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