class_xbox_ptu_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 ***************************************************************************************************/
34 
35 
42 XboxTeleopAtlascar::XboxTeleopAtlascar(int num_but, int num_axis)
43 {
44  num_buttons = num_but;
45  num_axes = num_axis;
46 
47  button.resize(num_but);
48  analog.resize(num_axes);
49 
50  steering_left_ang = 25.;
51  steering_right_ang = 22.;
52 
53 
56 
57  b_left_ang = 0.0;
58  b_right_ang = 0.0;
59 
60  speed_min = 0.0;
61  speed_max = 1.0;
62 
64  b_speed = 0.5;
65 
66  m_brake = -0.5;
67  b_brake = 0.5;
68 
69  for(uint i=0;i<button.size(); i++)
70  {
71  button[i] = 0;
72  }
73 
74  for(uint i=0;i<analog.size(); i++)
75  {
76  analog[i].toggled = 0;
77  }
78 
79  analog[BRAKE].val = 1.0;
80  analog[THROTTLE].val = 1.0;
81  analog[STEERING].val = 0.0;
82  analog[CLUTCH].val = 0.0;
83 
84  atlascar_cmd_ = nh_teleop.advertise<atlascar_base::AtlascarCommand>("/cmd_out", 1);
85  joy_sub_ = nh_teleop.subscribe<sensor_msgs::Joy>("/joy", 10, &XboxTeleopAtlascar::XboxCallback, this);
86 
87 };
88 
94 void XboxTeleopAtlascar::XboxCallback(const sensor_msgs::Joy::ConstPtr& joy)
95 {
96 
97 
98  //for the digital buttons
99  for(int i=0; i<num_buttons; i++)
100  {
101  if( joy->buttons[i])
102  {
103  button[i] = !button[i];
104  }
105  }
106  //for the analog buttons
107  for(int i=0; i<num_axes; i++)
108  {
109  if(!analog[i].toggled && ( fabs(joy->axes[i]) > 0.005 ))
110  analog[i].toggled = 1;
111 
112  if( fabs(analog[i].val -joy->axes[i]) > 0.005 && analog[i].toggled)
113  {
114  analog[i].val = joy->axes[i];
115  }
116  }
117 
118  command.auto_brake = button[MAN_AUTO_BRAKE];
119  command.auto_clutch = button[MAN_AUTO_CLUTCH];
120  command.auto_direction = button[MAN_AUTO_STEER];
121  command.auto_throttle = button[MAN_AUTO_THROTTLE];
122  command.auto_ignition = button[MAN_AUTO_IGNITION];
123 
124  command.emergency = button[E_STOP];
125  command.lights_high = button[HIGH_LIGHTS];
126  command.lights_medium = button[MEDIUM_LIGHTS];
127  command.lights_minimum = button[MEDIUM_LIGHTS];
128  command.ignition = button[START];
129  if(button[STOP])
130  {
131  button[START]=0;
132  command.ignition = 0;
133  }
134 
135  if(analog[STEERING].val>0)
136  command.steering_wheel = analog[STEERING].val*m_right_ang + b_right_ang;
137  else if(analog[STEERING].val<0)
138  {
139  command.steering_wheel = analog[STEERING].val*m_left_ang + b_left_ang;
140  }
141 
142  if(analog[CLUTCH].val>0)
143  {
144  command.clutch = analog[CLUTCH].val;
145  }else
146  command.clutch = 0.0;
147 
148 
149  command.brake = analog[BRAKE].val*m_brake+b_brake;
150  command.throttle = analog[THROTTLE].val*m_speed + b_speed;
151  command.speed = 0.0;
152  command.direct_control = 1;
153 
154  atlascar_cmd_.publish(command);
155 
156 };
157 
158 
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
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
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
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