36 #include <sensor_msgs/Joy.h>
37 #include <sensor_msgs/JointState.h>
42 #ifndef _ATLASCAR_XBOX_TELEOP_
43 #define _ATLASCAR_XBOX_TELEOP_
77 o<<
"toogle:"<<i.toggled<<
"\nval:"<<i.val<<endl;
83 enum{MAN_AUTO_STEER=0, MAN_AUTO_BRAKE=1, MAN_AUTO_THROTTLE=2, MAN_AUTO_CLUTCH=3, _B4=4, MAN_AUTO_IGNITION=5,\
84 START=6, E_STOP=7, _B8=8, _B9=9, HIGH_LIGHTS=10, WARNING_LIGHTS=11, MEDIUM_LIGHTS=12,\
87 enum{STEERING=0, _A1=1, BRAKE=2, _A3=3, CLUTCH=4, THROTTLE=5};
92 void XboxCallback(
const sensor_msgs::Joy::ConstPtr& joy);
94 ros::NodeHandle nh_teleop;
98 vector<TYPE_analog> analog;
122 int num_buttons, num_axes;
126 ros::Publisher atlascar_cmd_;
127 ros::Subscriber joy_sub_;
double m_speed
values to create the linear interpolation
double throttle_min
minimum & maximum throttle values
double speed_min
values to create the linear interpolation
friend ostream & operator<<(ostream &o, const TYPE_analog &i)
double brake_min
minimum & maximum brake values
struct to define a analog button
double steering_right_ang
double m_brake
values to create the linear interpolation
double clutch_min
minimum & maximum clutch values
This class simplifies the implementation of a interface between xbox and PTU.