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
00031 #include "class_xbox_teleop.h"
00032
00033
00040 XboxTeleopAtlascar::XboxTeleopAtlascar(int num_but, int num_axis)
00041 {
00042 num_buttons = num_but;
00043 num_axes = num_axis;
00044
00045 button.resize(num_but);
00046 analog.resize(num_axes);
00047
00048
00049 nh_teleop.getParam("/atlascar_base/steering_wheel_max", steering_max);
00050 nh_teleop.getParam("/atlascar_base/steering_wheel_min", steering_min);
00051
00052 nh_teleop.getParam("/atlascar_base/brake_max", brake_max);
00053 nh_teleop.getParam("/atlascar_base/brake_min", brake_min);
00054
00055 nh_teleop.getParam("/atlascar_base/clutch_max", clutch_max);
00056 nh_teleop.getParam("/atlascar_base/clutch_min", clutch_min);
00057
00058 nh_teleop.getParam("/atlascar_base/throttle_max", throttle_max);
00059 nh_teleop.getParam("/atlascar_base/throttle_min", throttle_min);
00060
00061 steering_left_ang = 25.;
00062 steering_right_ang = 22.;
00063
00064
00065 m_left_ang = steering_left_ang;
00066 m_right_ang = steering_right_ang;
00067
00068 b_left_ang = 0.0;
00069 b_right_ang = 0.0;
00070
00071 speed_min = 0.0;
00072 speed_max = 1.0;
00073
00074 m_speed = -(speed_max-speed_min)/2;
00075 b_speed = 0.5;
00076
00077 m_brake = -0.5;
00078 b_brake = 0.5;
00079
00080 for(uint i=0;i<button.size(); i++)
00081 {
00082 button[i] = 0;
00083 }
00084
00085 for(uint i=0;i<analog.size(); i++)
00086 {
00087 analog[i].toggled = 0;
00088 }
00089
00090 analog[BRAKE].val = 1.0;
00091 analog[THROTTLE].val = 1.0;
00092 analog[STEERING].val = 0.0;
00093 analog[CLUTCH].val = 0.0;
00094
00095 atlascar_cmd_ = nh_teleop.advertise<atlascar_base::AtlascarCommand>("/cmd_out", 1);
00096 joy_sub_ = nh_teleop.subscribe<sensor_msgs::Joy>("/joy", 10, &XboxTeleopAtlascar::XboxCallback, this);
00097
00098 };
00099
00105 void XboxTeleopAtlascar::XboxCallback(const sensor_msgs::Joy::ConstPtr& joy)
00106 {
00107
00108 for(int i=0; i<num_buttons; i++)
00109 {
00110 if( joy->buttons[i])
00111 {
00112 button[i] = !button[i];
00113 }
00114 }
00115
00116 for(int i=0; i<num_axes; i++)
00117 {
00118 if(!analog[i].toggled && ( fabs(joy->axes[i]) > 0.005 ))
00119 analog[i].toggled = 1;
00120
00121 if( fabs(analog[i].val -joy->axes[i]) > 0.005 && analog[i].toggled)
00122 {
00123 analog[i].val = joy->axes[i];
00124 }
00125 }
00126
00127 command.auto_brake = button[MAN_AUTO_BRAKE];
00128 command.auto_clutch = button[MAN_AUTO_CLUTCH];
00129 command.auto_direction = button[MAN_AUTO_STEER];
00130 command.auto_throttle = button[MAN_AUTO_THROTTLE];
00131 command.auto_ignition = button[MAN_AUTO_IGNITION];
00132
00133 command.emergency = button[E_STOP];
00134 command.lights_high = button[HIGH_LIGHTS];
00135 command.lights_medium = button[MEDIUM_LIGHTS];
00136 command.lights_minimum = button[MEDIUM_LIGHTS];
00137
00138 if(joy->buttons[START])
00139 command.ignition=1;
00140
00141 if(joy->buttons[STOP])
00142 command.ignition=0;
00143
00144 if(analog[STEERING].val>0)
00145 command.steering_wheel = analog[STEERING].val*steering_max;
00146 else if(analog[STEERING].val<0)
00147 command.steering_wheel = fabs(analog[STEERING].val)*steering_min;
00148
00149
00150 double m=throttle_max-throttle_min;
00151 double b=throttle_min;
00152
00153 command.throttle = ((-analog[THROTTLE].val+1)/2.)*m+b;
00154
00155 m=brake_max-brake_min;
00156 b=brake_min;
00157
00158 command.brake = ((-analog[BRAKE].val+1)/2.)*m+b;
00159
00160 m=clutch_max-clutch_min;
00161 b=clutch_min;
00162
00163 if(analog[CLUTCH].val>0)
00164 {
00165 command.clutch = analog[CLUTCH].val*m+b;
00166 }else
00167 command.clutch = clutch_min;
00168
00169 command.speed = 0.0;
00170 command.direct_control = 1;
00171
00172 atlascar_cmd_.publish(command);
00173 };
00174