00001 /************************************************************************************************** 00002 Software License Agreement (BSD License) 00003 00004 Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt 00005 All rights reserved. 00006 00007 Redistribution and use in source and binary forms, with or without modification, are permitted 00008 provided that the following conditions are met: 00009 00010 *Redistributions of source code must retain the above copyright notice, this list of 00011 conditions and the following disclaimer. 00012 *Redistributions in binary form must reproduce the above copyright notice, this list of 00013 conditions and the following disclaimer in the documentation and/or other materials provided 00014 with the distribution. 00015 *Neither the name of the University of Aveiro nor the names of its contributors may be used to 00016 endorse or promote products derived from this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR 00019 IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND 00020 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 00021 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00022 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00023 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER 00024 IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT 00025 OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 ***************************************************************************************************/ 00033 #include "class_xbox_teleop.h" 00034 00035 00042 XboxTeleopAtlascar::XboxTeleopAtlascar(int num_but, int num_axis) 00043 { 00044 num_buttons = num_but; 00045 num_axes = num_axis; 00046 00047 button.resize(num_but); 00048 analog.resize(num_axes); 00049 00050 steering_left_ang = 25.; 00051 steering_right_ang = 22.; 00052 00053 00054 m_left_ang = steering_left_ang; 00055 m_right_ang = steering_right_ang; 00056 00057 b_left_ang = 0.0; 00058 b_right_ang = 0.0; 00059 00060 speed_min = 0.0; 00061 speed_max = 1.0; 00062 00063 m_speed = -(speed_max-speed_min)/2; 00064 b_speed = 0.5; 00065 00066 m_brake = -0.5; 00067 b_brake = 0.5; 00068 00069 for(uint i=0;i<button.size(); i++) 00070 { 00071 button[i] = 0; 00072 } 00073 00074 for(uint i=0;i<analog.size(); i++) 00075 { 00076 analog[i].toggled = 0; 00077 } 00078 00079 analog[BRAKE].val = 1.0; 00080 analog[THROTTLE].val = 1.0; 00081 analog[STEERING].val = 0.0; 00082 analog[CLUTCH].val = 0.0; 00083 00084 atlascar_cmd_ = nh_teleop.advertise<atlascar_base::AtlascarCommand>("/cmd_out", 1); 00085 joy_sub_ = nh_teleop.subscribe<sensor_msgs::Joy>("/joy", 10, &XboxTeleopAtlascar::XboxCallback, this); 00086 00087 }; 00088 00094 void XboxTeleopAtlascar::XboxCallback(const sensor_msgs::Joy::ConstPtr& joy) 00095 { 00096 00097 00098 //for the digital buttons 00099 for(int i=0; i<num_buttons; i++) 00100 { 00101 if( joy->buttons[i]) 00102 { 00103 button[i] = !button[i]; 00104 } 00105 } 00106 //for the analog buttons 00107 for(int i=0; i<num_axes; i++) 00108 { 00109 if(!analog[i].toggled && ( fabs(joy->axes[i]) > 0.005 )) 00110 analog[i].toggled = 1; 00111 00112 if( fabs(analog[i].val -joy->axes[i]) > 0.005 && analog[i].toggled) 00113 { 00114 analog[i].val = joy->axes[i]; 00115 } 00116 } 00117 00118 command.auto_brake = button[MAN_AUTO_BRAKE]; 00119 command.auto_clutch = button[MAN_AUTO_CLUTCH]; 00120 command.auto_direction = button[MAN_AUTO_STEER]; 00121 command.auto_throttle = button[MAN_AUTO_THROTTLE]; 00122 command.auto_ignition = button[MAN_AUTO_IGNITION]; 00123 00124 command.emergency = button[E_STOP]; 00125 command.lights_high = button[HIGH_LIGHTS]; 00126 command.lights_medium = button[MEDIUM_LIGHTS]; 00127 command.lights_minimum = button[MEDIUM_LIGHTS]; 00128 command.ignition = button[START]; 00129 if(button[STOP]) 00130 { 00131 button[START]=0; 00132 command.ignition = 0; 00133 } 00134 00135 if(analog[STEERING].val>0) 00136 command.steering_wheel = analog[STEERING].val*m_right_ang + b_right_ang; 00137 else if(analog[STEERING].val<0) 00138 { 00139 command.steering_wheel = analog[STEERING].val*m_left_ang + b_left_ang; 00140 } 00141 00142 if(analog[CLUTCH].val>0) 00143 { 00144 command.clutch = analog[CLUTCH].val; 00145 }else 00146 command.clutch = 0.0; 00147 00148 00149 command.brake = analog[BRAKE].val*m_brake+b_brake; 00150 command.throttle = analog[THROTTLE].val*m_speed + b_speed; 00151 command.speed = 0.0; 00152 command.direct_control = 1; 00153 00154 atlascar_cmd_.publish(command); 00155 00156 }; 00157 00158