Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 #ifndef JOYSTICKDEMO_H_
00036 #define JOYSTICKDEMO_H_
00037 
00038 #include <ros/ros.h>
00039 #include <sensor_msgs/Joy.h>
00040 #include <std_msgs/Empty.h>
00041 
00042 #include <dbw_fca_msgs/ThrottleCmd.h>
00043 #include <dbw_fca_msgs/BrakeCmd.h>
00044 #include <dbw_fca_msgs/SteeringCmd.h>
00045 #include <dbw_fca_msgs/GearCmd.h>
00046 #include <dbw_fca_msgs/TurnSignalCmd.h>
00047 
00048 typedef struct {
00049   ros::Time stamp;
00050   float brake_joy;
00051   float throttle_joy;
00052   float steering_joy;
00053   bool steering_mult;
00054   int gear_cmd;
00055   int turn_signal_cmd;
00056   bool joy_throttle_valid;
00057   bool joy_brake_valid;
00058 } JoystickDataStruct;
00059 
00060 class JoystickDemo {
00061 public:
00062   JoystickDemo(ros::NodeHandle &node, ros::NodeHandle &priv_nh);
00063 private:
00064   void recvJoy(const sensor_msgs::Joy::ConstPtr& msg);
00065   void cmdCallback(const ros::TimerEvent& event);
00066 
00067   
00068   ros::Subscriber sub_joy_;
00069   ros::Publisher pub_brake_;
00070   ros::Publisher pub_throttle_;
00071   ros::Publisher pub_steering_;
00072   ros::Publisher pub_gear_;
00073   ros::Publisher pub_turn_signal_;
00074   ros::Publisher pub_enable_;
00075   ros::Publisher pub_disable_;
00076 
00077   
00078   bool brake_; 
00079   bool throttle_; 
00080   bool steer_; 
00081   bool shift_; 
00082   bool signal_; 
00083 
00084   
00085   float brake_gain_; 
00086   float throttle_gain_; 
00087 
00088   
00089   bool ignore_; 
00090   bool enable_; 
00091   bool count_; 
00092   bool strq_; 
00093   float svel_; 
00094 
00095   
00096   ros::Timer timer_;
00097   JoystickDataStruct data_;
00098   sensor_msgs::Joy joy_;
00099   uint8_t counter_;
00100   float last_steering_filt_output_;
00101 
00102   enum {
00103     BTN_PARK = 3,
00104     BTN_REVERSE = 1,
00105     BTN_NEUTRAL = 2,
00106     BTN_DRIVE = 0,
00107     BTN_ENABLE = 5,
00108     BTN_DISABLE = 4,
00109     BTN_STEER_MULT_1 = 6,
00110     BTN_STEER_MULT_2 = 7,
00111     BTN_COUNT_X = 11,
00112     BTN_COUNT_D = 12,
00113     AXIS_THROTTLE = 5,
00114     AXIS_BRAKE = 2,
00115     AXIS_STEER_1 = 0,
00116     AXIS_STEER_2 = 3,
00117     AXIS_TURN_SIG = 6,
00118     AXIS_COUNT_D = 6,
00119     AXIS_COUNT_X = 8,
00120   };
00121 };
00122 
00123 #endif 
00124