00001 #include "ros/ros.h" 00002 #include "sensor_msgs/Joy.h" 00003 #include "geometry_msgs/Twist.h" 00004 #include "im_msgs/SetRGB.h" 00005 00006 #include <diagnostic_updater/diagnostic_updater.h> 00007 #include <diagnostic_updater/publisher.h> 00008 00009 #include "IMEIO.h" 00010 #include "ErrorCodes.h" 00011 00012 using namespace std; 00013 00014 class IMJoystick 00015 { 00016 public: 00017 ros::NodeHandle n; 00018 geometry_msgs::Twist cmd; 00019 00020 double max_lin, max_ang; 00021 double max_x, max_z; 00022 bool deadman; 00023 00024 double d_timeout; 00025 00026 ros::Publisher vel_pub; 00027 ros::Subscriber joy_sub_; 00028 ros::ServiceClient client; 00029 00030 IMJoystick(); 00031 ~IMJoystick(){} 00032 void init(); 00033 void CallbackJoy(const sensor_msgs::Joy::ConstPtr& joy_msg); 00034 void PublishVel(); 00035 void CallRGBService(); 00036 void TurnOffRGB(); 00037 00038 private: 00039 int deadman_button; 00040 int axr_leftwards; 00041 int axr_upwards; 00042 00043 int axl_leftwards; 00044 int axl_upwards; 00045 00046 int triangle_button, cross_button, square_button, circle_button; 00047 00048 ros::Time last_time; 00049 geometry_msgs::Twist vel_msg; 00050 00051 void CheckTimeout(); 00052 };