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
00036 #ifndef JOYSTICKDEMO_H_
00037 #define JOYSTICKDEMO_H_
00038
00039 #include <ros/ros.h>
00040 #include <sensor_msgs/Joy.h>
00041 #include <std_msgs/Empty.h>
00042
00043 #include <dbw_pacifica_msgs/AcceleratorPedalCmd.h>
00044 #include <dbw_pacifica_msgs/BrakeCmd.h>
00045 #include <dbw_pacifica_msgs/SteeringCmd.h>
00046 #include <dbw_pacifica_msgs/GearCmd.h>
00047 #include <dbw_pacifica_msgs/MiscCmd.h>
00048 #include <dbw_pacifica_msgs/GlobalEnableCmd.h>
00049
00050 namespace joystick_demo
00051 {
00052
00053 typedef struct {
00054 ros::Time stamp;
00055 float brake_joy;
00056 float accelerator_pedal_joy;
00057 float steering_joy;
00058 bool steering_mult;
00059 int gear_cmd;
00060 int turn_signal_cmd;
00061 bool joy_accelerator_pedal_valid;
00062 bool joy_brake_valid;
00063 float accel_decel_limits;
00064 } JoystickDataStruct;
00065
00066 class JoystickDemo {
00067 public:
00068 JoystickDemo(ros::NodeHandle &node, ros::NodeHandle &priv_nh);
00069 private:
00070 void recvJoy(const sensor_msgs::Joy::ConstPtr& msg);
00071 void cmdCallback(const ros::TimerEvent& event);
00072
00073
00074 ros::Subscriber sub_joy_;
00075 ros::Publisher pub_accelerator_pedal_;
00076 ros::Publisher pub_brake_;
00077 ros::Publisher pub_steering_;
00078 ros::Publisher pub_gear_;
00079 ros::Publisher pub_misc_;
00080 ros::Publisher pub_enable_;
00081 ros::Publisher pub_disable_;
00082 ros::Publisher pub_global_enable_;
00083
00084 bool ignore_;
00085 bool enable_;
00086 bool count_;
00087 double svel_;
00088
00089
00090 ros::Timer timer_;
00091 JoystickDataStruct data_;
00092 sensor_msgs::Joy joy_;
00093 uint8_t counter_;
00094
00095 enum {
00096 BTN_PARK = 3,
00097 BTN_REVERSE = 1,
00098 BTN_NEUTRAL = 2,
00099 BTN_DRIVE = 0,
00100 BTN_ENABLE = 5,
00101 BTN_DISABLE = 4,
00102 BTN_STEER_MULT_1 = 6,
00103 BTN_STEER_MULT_2 = 7,
00104 BTN_COUNT = 11,
00105 AXIS_ACCELERATOR_PEDAL = 5,
00106 AXIS_BRAKE = 2,
00107 AXIS_STEER_1 = 0,
00108 AXIS_STEER_2 = 3,
00109 AXIS_TURN_SIG = 6,
00110 AXIS_COUNT = 8,
00111 };
00112 };
00113
00114 }
00115
00116 #endif