00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC. 00002 // Author Jose Luis Rivero <jrivero@iri.upc.edu> 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 _iri_joystick_driver_node_h_ 00026 #define _iri_joystick_driver_node_h_ 00027 00028 #include "iri_base_driver/iri_base_driver_node.h" 00029 #include "iri_joystick_driver.h" 00030 #include <sensor_msgs/Joy.h> 00031 00049 class IriJoystickDriverNode : public iri_base_driver::IriBaseNodeDriver<IriJoystickDriver> 00050 { 00051 private: 00052 ros::Publisher joy_mov_pub_; 00053 std::string joy_mov_pub_name_; 00054 00055 /* total number of axes events generated (could be different of published) */ 00056 double total_axes_events_; 00057 /* total number of buttons events generated (could be different of published) */ 00058 double total_button_events_; 00059 /* total number of joy msg published in the joy_mob_pub_ topic */ 00060 double total_joy_msg_sent_; 00061 00062 /* 00063 * publish the joy message through the topic defined in joy_mov_pub 00064 */ 00065 void publish_joy_msg(const sensor_msgs::Joy & msg); 00066 /* 00067 * wrapper function (need to be static) just a bridge to 00068 * move_joystick_callback function. 00069 */ 00070 static void wrapper_move_joystick_callback(void * param, unsigned int axis_id, float value); 00071 /* 00072 * callback when moving the axes in the joystick. publish a JOY message 00073 * on the topic (see JOY package for more info). 00074 */ 00075 void move_joystick_callback(unsigned int axis_id, float value); 00076 00077 /* 00078 * wrapper function (need to be static) just a bridge to 00079 * move_joystick_callback function. 00080 */ 00081 static void wrapper_button_callback(void * param, unsigned int button_id, bool level); 00082 /* 00083 * callback when pressing buttonsin the joystick. publish a JOY message 00084 * on the topic with button info (see JOY package for more info). 00085 */ 00086 void button_callback(unsigned int button_id, bool level); 00087 00095 void postNodeOpenHook(void); 00096 00097 public: 00115 IriJoystickDriverNode(ros::NodeHandle& nh); 00116 00123 ~IriJoystickDriverNode(); 00124 00125 protected: 00126 // [diagnostic functions] 00127 void joystick_check(diagnostic_updater::DiagnosticStatusWrapper &stat); 00128 00141 void mainNodeThread(void); 00142 00153 void addNodeDiagnostics(void); 00154 00155 // [driver test functions] 00156 00166 void addNodeOpenedTests(void); 00167 00177 void addNodeStoppedTests(void); 00178 00188 void addNodeRunningTests(void); 00189 00197 void reconfigureNodeHook(int level); 00198 }; 00199 00200 #endif