35 #include <sensor_msgs/Joy.h>
36 #include <atlascar_base/AtlascarCommand.h>
39 #ifndef _ATLASCAR_XBOX_TELEOP_
40 #define _ATLASCAR_XBOX_TELEOP_
71 o<<
"toogle:"<<i.
toggled<<
"\nval:"<<i.
val<<endl;
77 enum{MAN_AUTO_STEER=0, MAN_AUTO_BRAKE=1, MAN_AUTO_THROTTLE=2, MAN_AUTO_CLUTCH=3, _B4=4, MAN_AUTO_IGNITION=5,\
78 START=6, E_STOP=7, _B8=8, _B9=9, HIGH_LIGHTS=10, WARNING_LIGHTS=11, MEDIUM_LIGHTS=12,\
81 enum{STEERING=0, _A1=1, BRAKE=2, _A3=3, CLUTCH=4, THROTTLE=5};
91 void XboxCallback(
const sensor_msgs::Joy::ConstPtr& joy);
float speed_min
car speed limits
ros::Publisher atlascar_cmd_
method just to publish the base message
atlascar_base::AtlascarCommand command
struct with the Atlascar Base Command message
int num_buttons
variable with number of digital buttons and analog axis
ros::Subscriber joy_sub_
method to subscribe the gamepad message
friend ostream & operator<<(ostream &o, const TYPE_analog &i)
ros::NodeHandle nh_teleop
float m_speed
line segment slope to calculate whished car speed value
struct to define a analog button
float m_brake
line segment slope to calculate whished car speed value
vector< int > button
vector with all digital buttons status
vector< TYPE_analog > analog
vector with analog/axis values
This class simplifies the implementation of a interface between xbox and PTU.