class_xbox_teleop.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 
33 
40 XboxTeleopAtlascar::XboxTeleopAtlascar(int num_but, int num_axis)
41 {
42  num_buttons = num_but;
43  num_axes = num_axis;
44 
45  button.resize(num_but);
46  analog.resize(num_axes);
47 
48 
49  nh_teleop.getParam("/atlascar_base/steering_wheel_max", steering_max);
50  nh_teleop.getParam("/atlascar_base/steering_wheel_min", steering_min);
51 
52  nh_teleop.getParam("/atlascar_base/brake_max", brake_max);
53  nh_teleop.getParam("/atlascar_base/brake_min", brake_min);
54 
55  nh_teleop.getParam("/atlascar_base/clutch_max", clutch_max);
56  nh_teleop.getParam("/atlascar_base/clutch_min", clutch_min);
57 
58  nh_teleop.getParam("/atlascar_base/throttle_max", throttle_max);
59  nh_teleop.getParam("/atlascar_base/throttle_min", throttle_min);
60 
61  steering_left_ang = 25.;
62  steering_right_ang = 22.;
63 
64 
67 
68  b_left_ang = 0.0;
69  b_right_ang = 0.0;
70 
71  speed_min = 0.0;
72  speed_max = 1.0;
73 
75  b_speed = 0.5;
76 
77  m_brake = -0.5;
78  b_brake = 0.5;
79 
80  for(uint i=0;i<button.size(); i++)
81  {
82  button[i] = 0;
83  }
84 
85  for(uint i=0;i<analog.size(); i++)
86  {
87  analog[i].toggled = 0;
88  }
89 
90  analog[BRAKE].val = 1.0;
91  analog[THROTTLE].val = 1.0;
92  analog[STEERING].val = 0.0;
93  analog[CLUTCH].val = 0.0;
94 
95 // atlascar_cmd_ = nh_teleop.advertise<atlascar_base::AtlascarCommand>("/cmd_out", 1);
96  joy_sub_ = nh_teleop.subscribe<sensor_msgs::Joy>("/joy", 10, &XboxTeleopAtlascar::XboxCallback, this);
97 
98 };
99 
105 void XboxTeleopAtlascar::XboxCallback(const sensor_msgs::Joy::ConstPtr& joy)
106 {
107  //for the digital buttons
108  for(int i=0; i<num_buttons; i++)
109  {
110  if( joy->buttons[i])
111  {
112  button[i] = !button[i];
113  }
114  }
115  //for the analog buttons
116  for(int i=0; i<num_axes; i++)
117  {
118  if(!analog[i].toggled && ( fabs(joy->axes[i]) > 0.005 ))
119  analog[i].toggled = 1;
120 
121  if( fabs(analog[i].val -joy->axes[i]) > 0.005 && analog[i].toggled)
122  {
123  analog[i].val = joy->axes[i];
124  }
125  }
126 
127 // command.auto_brake = button[MAN_AUTO_BRAKE];
128 // command.auto_clutch = button[MAN_AUTO_CLUTCH];
129 // command.auto_direction = button[MAN_AUTO_STEER];
130 // command.auto_throttle = button[MAN_AUTO_THROTTLE];
131 // command.auto_ignition = button[MAN_AUTO_IGNITION];
132 //
133 // command.emergency = button[E_STOP];
134 // command.lights_high = button[HIGH_LIGHTS];
135 // command.lights_medium = button[MEDIUM_LIGHTS];
136 // command.lights_minimum = button[MEDIUM_LIGHTS];
137 
138 // if(joy->buttons[START])
139 // command.ignition=1;
140 //
141 // if(joy->buttons[STOP])
142 // command.ignition=0;
143 
144 // if(analog[STEERING].val>0)
145 // command.steering_wheel = analog[STEERING].val*steering_max;
146 // else if(analog[STEERING].val<0)
147 // command.steering_wheel = fabs(analog[STEERING].val)*steering_min;
148 //
149 
150 // double m=throttle_max-throttle_min;
151 // double b=throttle_min;
152 
153 // command.throttle = ((-analog[THROTTLE].val+1)/2.)*m+b;
154 
155 // m=brake_max-brake_min;
156 // b=brake_min;
157 
158 // command.brake = ((-analog[BRAKE].val+1)/2.)*m+b;
159 
160 // m=clutch_max-clutch_min;
161 // b=clutch_min;
162 
163 // if(analog[CLUTCH].val>0)
164 // {
165 // command.clutch = analog[CLUTCH].val*m+b;
166 // }else
167 // command.clutch = clutch_min;
168 //
169 // command.speed = 0.0;
170 // command.direct_control = 1;
171 
172 // atlascar_cmd_.publish(command);
173 };
174 
float speed_min
car speed limits
double throttle_min
minimum & maximum throttle values
void XboxCallback(const sensor_msgs::Joy::ConstPtr &joy)
callback that is called when a xbox msg is received
int num_buttons
variable with number of digital buttons and analog axis
ros::Subscriber joy_sub_
method to subscribe the gamepad message
float steering_left_ang
limit values for the steering angles
ros::NodeHandle nh_teleop
XboxTeleopAtlascar(int num_but, int num_axis)
constructor
float m_speed
line segment slope to calculate whished car speed value
double brake_min
minimum & maximum brake values
class_xbpox_teleop.h file for this node. Includes, class global vars, class methods, etc.
float m_brake
line segment slope to calculate whished car speed value
vector< int > button
vector with all digital buttons status
double clutch_min
minimum & maximum clutch values
double steering_max
minimum & maximum steering angle values
float m_left_ang
line segment slope, left side and right side
vector< TYPE_analog > analog
vector with analog/axis values


atlascar_teleop
Author(s): David Gameiro
autogenerated on Mon Mar 2 2015 01:31:27