JoystickDemo.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018-2019, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include "JoystickDemo.h"
36 
38 {
39  joy_.axes.resize(AXIS_COUNT_X, 0);
40  joy_.buttons.resize(BTN_COUNT_X, 0);
41 
42  brake_ = true;
43  throttle_ = true;
44  steer_ = true;
45  shift_ = true;
46  signal_ = true;
47  priv_nh.getParam("brake", brake_);
48  priv_nh.getParam("throttle", throttle_);
49  priv_nh.getParam("steer", steer_);
50  priv_nh.getParam("shift", shift_);
51  priv_nh.getParam("signal", signal_);
52 
53  brake_gain_ = 1.0;
54  throttle_gain_ = 1.0;
55  priv_nh.getParam("brake_gain", brake_gain_);
56  priv_nh.getParam("throttle_gain", throttle_gain_);
57  brake_gain_ = std::min(std::max(brake_gain_, (float)0), (float)1);
58  throttle_gain_ = std::min(std::max(throttle_gain_, (float)0), (float)1);
59 
60  ignore_ = false;
61  enable_ = true;
62  count_ = false;
63  strq_ = false;
64  svel_ = 0.0;
66  priv_nh.getParam("ignore", ignore_);
67  priv_nh.getParam("enable", enable_);
68  priv_nh.getParam("count", count_);
69  priv_nh.getParam("strq", strq_);
70  priv_nh.getParam("svel", svel_);
71 
72  sub_joy_ = node.subscribe("/joy", 1, &JoystickDemo::recvJoy, this);
73 
74  data_.brake_joy = 0.0;
75  data_.gear_cmd = dbw_fca_msgs::Gear::NONE;
76  data_.steering_joy = 0.0;
77  data_.steering_mult = false;
78  data_.throttle_joy = 0.0;
79  data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::NONE;
80  data_.door_select = dbw_fca_msgs::DoorCmd::NONE;
81  data_.door_action = dbw_fca_msgs::DoorCmd::NONE;
82  data_.joy_throttle_valid = false;
83  data_.joy_brake_valid = false;
84 
85  if (brake_) {
86  pub_brake_ = node.advertise<dbw_fca_msgs::BrakeCmd>("brake_cmd", 1);
87  }
88  if (throttle_) {
89  pub_throttle_ = node.advertise<dbw_fca_msgs::ThrottleCmd>("throttle_cmd", 1);
90  }
91  if (steer_) {
92  pub_steering_ = node.advertise<dbw_fca_msgs::SteeringCmd>("steering_cmd", 1);
93  }
94  if (shift_) {
95  pub_gear_ = node.advertise<dbw_fca_msgs::GearCmd>("gear_cmd", 1);
96  }
97  if (signal_) {
98  pub_turn_signal_ = node.advertise<dbw_fca_msgs::TurnSignalCmd>("turn_signal_cmd", 1);
99  }
100  if (enable_) {
101  pub_enable_ = node.advertise<std_msgs::Empty>("enable", 1);
102  pub_disable_ = node.advertise<std_msgs::Empty>("disable", 1);
103  }
104 
105  timer_ = node.createTimer(ros::Duration(0.02), &JoystickDemo::cmdCallback, this);
106 }
107 
109 {
110  // Detect joy timeouts and reset
111  if (event.current_real - data_.stamp > ros::Duration(0.1)) {
112  data_.joy_throttle_valid = false;
113  data_.joy_brake_valid = false;
115  return;
116  }
117 
118  // Optional watchdog counter
119  if (count_) {
120  counter_++;
121  }
122 
123  // Brake
124  if (brake_) {
125  dbw_fca_msgs::BrakeCmd msg;
126  msg.enable = true;
127  msg.ignore = ignore_;
128  msg.count = counter_;
129  msg.pedal_cmd_type = dbw_fca_msgs::BrakeCmd::CMD_PERCENT;
130  msg.pedal_cmd = data_.brake_joy * brake_gain_;
132  }
133 
134  // Throttle
135  if (throttle_) {
136  dbw_fca_msgs::ThrottleCmd msg;
137  msg.enable = true;
138  msg.ignore = ignore_;
139  msg.count = counter_;
140  msg.pedal_cmd_type = dbw_fca_msgs::ThrottleCmd::CMD_PERCENT;
141  msg.pedal_cmd = data_.throttle_joy * throttle_gain_;
143  }
144 
145  // Steering
146  if (steer_) {
147  dbw_fca_msgs::SteeringCmd msg;
148  msg.enable = true;
149  msg.ignore = ignore_;
150  msg.count = counter_;
151  if (!strq_) {
152  msg.cmd_type = dbw_fca_msgs::SteeringCmd::CMD_ANGLE;
153 
154  float raw_steering_cmd;
155  if (data_.steering_mult) {
156  raw_steering_cmd = dbw_fca_msgs::SteeringCmd::ANGLE_MAX * data_.steering_joy;
157  } else {
158  raw_steering_cmd = 0.5 * dbw_fca_msgs::SteeringCmd::ANGLE_MAX * data_.steering_joy;
159  }
160 
161  float tau = 0.1;
162  float filtered_steering_cmd = 0.02 / tau * raw_steering_cmd + (1 - 0.02 / tau) * last_steering_filt_output_;
163  last_steering_filt_output_ = filtered_steering_cmd;
164 
165  msg.steering_wheel_angle_velocity = svel_;
166  msg.steering_wheel_angle_cmd = filtered_steering_cmd;
167  } else {
168  msg.cmd_type = dbw_fca_msgs::SteeringCmd::CMD_TORQUE;
169  msg.steering_wheel_torque_cmd = dbw_fca_msgs::SteeringCmd::TORQUE_MAX * data_.steering_joy;
170  }
172  }
173 
174  // Gear
175  if (shift_) {
176  if (data_.gear_cmd != dbw_fca_msgs::Gear::NONE) {
177  dbw_fca_msgs::GearCmd msg;
178  msg.cmd.gear = data_.gear_cmd;
180  }
181  }
182 
183  // Turn signal
184  if (signal_) {
186  msg.cmd.value = data_.turn_signal_cmd;
187  msg.door.select = data_.door_select;
188  msg.door.action = data_.door_action;
190  }
191 }
192 
193 void JoystickDemo::recvJoy(const sensor_msgs::Joy::ConstPtr& msg)
194 {
195  // Check for expected sizes
196  if (msg->axes.size() != (size_t)AXIS_COUNT_X && msg->buttons.size() != (size_t)BTN_COUNT_X) {
197  if (msg->axes.size() == (size_t)AXIS_COUNT_D && msg->buttons.size() == (size_t)BTN_COUNT_D) {
198  ROS_ERROR_THROTTLE(2.0, "Detected Logitech Gamepad F310 in DirectInput (D) mode. Please select (X) with the switch on the back to select XInput mode.");
199  }
200  if (msg->axes.size() != (size_t)AXIS_COUNT_X) {
201  ROS_ERROR_THROTTLE(2.0, "Expected %zu joy axis count, received %zu", (size_t)AXIS_COUNT_X, msg->axes.size());
202  }
203  if (msg->buttons.size() != (size_t)BTN_COUNT_X) {
204  ROS_ERROR_THROTTLE(2.0, "Expected %zu joy button count, received %zu", (size_t)BTN_COUNT_X, msg->buttons.size());
205  }
206  return;
207  }
208 
209  // Handle joystick startup
210  if (msg->axes[AXIS_THROTTLE] != 0.0) {
211  data_.joy_throttle_valid = true;
212  }
213  if (msg->axes[AXIS_BRAKE] != 0.0) {
214  data_.joy_brake_valid = true;
215  }
216 
217  // Throttle
219  data_.throttle_joy = 0.5 - 0.5 * msg->axes[AXIS_THROTTLE];
220  }
221 
222  // Brake
223  if (data_.joy_brake_valid) {
224  data_.brake_joy = 0.5 - 0.5 * msg->axes[AXIS_BRAKE];
225  }
226 
227  // Gear
228  if (msg->buttons[BTN_PARK]) {
229  data_.gear_cmd = dbw_fca_msgs::Gear::PARK;
230  } else if (msg->buttons[BTN_REVERSE]) {
231  data_.gear_cmd = dbw_fca_msgs::Gear::REVERSE;
232  } else if (msg->buttons[BTN_DRIVE]) {
233  data_.gear_cmd = dbw_fca_msgs::Gear::DRIVE;
234  } else if (msg->buttons[BTN_NEUTRAL]) {
235  data_.gear_cmd = dbw_fca_msgs::Gear::NEUTRAL;
236  } else {
237  data_.gear_cmd = dbw_fca_msgs::Gear::NONE;
238  }
239 
240  // Steering
241  data_.steering_joy = (fabs(msg->axes[AXIS_STEER_1]) > fabs(msg->axes[AXIS_STEER_2])) ? msg->axes[AXIS_STEER_1] : msg->axes[AXIS_STEER_2];
242  data_.steering_mult = msg->buttons[BTN_STEER_MULT_1] || msg->buttons[BTN_STEER_MULT_2];
243 
244  // Turn signal
245  if (msg->axes[AXIS_TURN_SIG] != joy_.axes[AXIS_TURN_SIG]) {
246  if (fabs(msg->axes[AXIS_DOOR_ACTION]) < 0.5) {
247  switch (data_.turn_signal_cmd) {
248  case dbw_fca_msgs::TurnSignal::NONE:
249  if (msg->axes[AXIS_TURN_SIG] < -0.5) {
250  data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::RIGHT;
251  } else if (msg->axes[AXIS_TURN_SIG] > 0.5) {
252  data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::LEFT;
253  }
254  break;
255  case dbw_fca_msgs::TurnSignal::LEFT:
256  if (msg->axes[AXIS_TURN_SIG] < -0.5) {
257  data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::RIGHT;
258  } else if (msg->axes[AXIS_TURN_SIG] > 0.5) {
259  data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::NONE;
260  }
261  break;
262  case dbw_fca_msgs::TurnSignal::RIGHT:
263  if (msg->axes[AXIS_TURN_SIG] < -0.5) {
264  data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::NONE;
265  } else if (msg->axes[AXIS_TURN_SIG] > 0.5) {
266  data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::LEFT;
267  }
268  break;
269  }
270  }
271  }
272 
273  // Doors and trunk
274  data_.door_select = dbw_fca_msgs::DoorCmd::NONE;
275  data_.door_action = dbw_fca_msgs::DoorCmd::NONE;
276  if (msg->buttons[BTN_TRUNK_OPEN]) {
277  data_.door_select = dbw_fca_msgs::DoorCmd::TRUNK;
278  data_.door_action = dbw_fca_msgs::DoorCmd::OPEN;
279  } else if (msg->buttons[BTN_TRUNK_CLOSE]) {
280  data_.door_select = dbw_fca_msgs::DoorCmd::TRUNK;
281  data_.door_action = dbw_fca_msgs::DoorCmd::CLOSE;
282  }
283  if (msg->axes[AXIS_DOOR_ACTION] > 0.5) {
284  if (msg->axes[AXIS_DOOR_SELECT] < -0.5) {
285  data_.door_select = dbw_fca_msgs::DoorCmd::RIGHT;
286  data_.door_action = dbw_fca_msgs::DoorCmd::OPEN;
287  } else if (msg->axes[AXIS_TURN_SIG] > 0.5) {
288  data_.door_select = dbw_fca_msgs::DoorCmd::LEFT;
289  data_.door_action = dbw_fca_msgs::DoorCmd::OPEN;
290  }
291  }
292  if (msg->axes[AXIS_DOOR_ACTION] < -0.5) {
293  if (msg->axes[AXIS_DOOR_SELECT] < -0.5) {
294  data_.door_select = dbw_fca_msgs::DoorCmd::RIGHT;
295  data_.door_action = dbw_fca_msgs::DoorCmd::CLOSE;
296  } else if (msg->axes[AXIS_TURN_SIG] > 0.5) {
297  data_.door_select = dbw_fca_msgs::DoorCmd::LEFT;
298  data_.door_action = dbw_fca_msgs::DoorCmd::CLOSE;
299  }
300  }
301 
302  // Optional enable and disable buttons
303  if (enable_) {
304  const std_msgs::Empty empty;
305  if (msg->buttons[BTN_ENABLE]) {
306  pub_enable_.publish(empty);
307  }
308  if (msg->buttons[BTN_DISABLE]) {
309  pub_disable_.publish(empty);
310  }
311  }
312 
314  joy_ = *msg;
315 }
316 
ROS_ERROR_THROTTLE
#define ROS_ERROR_THROTTLE(period,...)
JoystickDemo::strq_
bool strq_
Definition: JoystickDemo.h:94
JoystickDemo::BTN_STEER_MULT_2
@ BTN_STEER_MULT_2
Definition: JoystickDemo.h:112
JoystickDemo::AXIS_TURN_SIG
@ AXIS_TURN_SIG
Definition: JoystickDemo.h:121
JoystickDataStruct::turn_signal_cmd
int turn_signal_cmd
Definition: JoystickDemo.h:87
JoystickDemo::BTN_STEER_MULT_1
@ BTN_STEER_MULT_1
Definition: JoystickDemo.h:111
JoystickDemo::throttle_gain_
float throttle_gain_
Definition: JoystickDemo.h:88
msg
msg
JoystickDemo::pub_gear_
ros::Publisher pub_gear_
Definition: JoystickDemo.h:74
JoystickDemo::steer_
bool steer_
Definition: JoystickDemo.h:82
dbw_fca_msgs::TurnSignalCmd
MiscCmd TurnSignalCmd
JoystickDemo::BTN_COUNT_X
@ BTN_COUNT_X
Definition: JoystickDemo.h:115
JoystickDemo.h
JoystickDemo::pub_disable_
ros::Publisher pub_disable_
Definition: JoystickDemo.h:77
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
JoystickDemo::AXIS_STEER_2
@ AXIS_STEER_2
Definition: JoystickDemo.h:120
JoystickDemo::BTN_COUNT_D
@ BTN_COUNT_D
Definition: JoystickDemo.h:116
JoystickDemo::pub_turn_signal_
ros::Publisher pub_turn_signal_
Definition: JoystickDemo.h:75
JoystickDemo::pub_brake_
ros::Publisher pub_brake_
Definition: JoystickDemo.h:71
JoystickDemo::throttle_
bool throttle_
Definition: JoystickDemo.h:81
JoystickDemo::BTN_REVERSE
@ BTN_REVERSE
Definition: JoystickDemo.h:106
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
JoystickDemo::BTN_ENABLE
@ BTN_ENABLE
Definition: JoystickDemo.h:109
JoystickDemo::ignore_
bool ignore_
Definition: JoystickDemo.h:91
JoystickDemo::AXIS_DOOR_SELECT
@ AXIS_DOOR_SELECT
Definition: JoystickDemo.h:122
JoystickDemo::BTN_NEUTRAL
@ BTN_NEUTRAL
Definition: JoystickDemo.h:107
JoystickDataStruct::steering_mult
bool steering_mult
Definition: JoystickDemo.h:85
JoystickDemo::joy_
sensor_msgs::Joy joy_
Definition: JoystickDemo.h:100
JoystickDemo::counter_
uint8_t counter_
Definition: JoystickDemo.h:101
JoystickDemo::signal_
bool signal_
Definition: JoystickDemo.h:84
JoystickDemo::pub_steering_
ros::Publisher pub_steering_
Definition: JoystickDemo.h:73
JoystickDemo::sub_joy_
ros::Subscriber sub_joy_
Definition: JoystickDemo.h:70
JoystickDemo::enable_
bool enable_
Definition: JoystickDemo.h:92
JoystickDataStruct::steering_joy
float steering_joy
Definition: JoystickDemo.h:84
JoystickDemo::BTN_TRUNK_OPEN
@ BTN_TRUNK_OPEN
Definition: JoystickDemo.h:113
JoystickDemo::recvJoy
void recvJoy(const sensor_msgs::Joy::ConstPtr &msg)
Definition: JoystickDemo.cpp:193
JoystickDataStruct::brake_joy
float brake_joy
Definition: JoystickDemo.h:82
JoystickDemo::AXIS_STEER_1
@ AXIS_STEER_1
Definition: JoystickDemo.h:119
JoystickDataStruct::door_action
int door_action
Definition: JoystickDemo.h:89
JoystickDataStruct::throttle_joy
float throttle_joy
Definition: JoystickDemo.h:83
JoystickDemo::brake_
bool brake_
Definition: JoystickDemo.h:80
ros::TimerEvent
ros::TimerEvent::current_real
Time current_real
JoystickDemo::svel_
float svel_
Definition: JoystickDemo.h:95
JoystickDataStruct::gear_cmd
int gear_cmd
Definition: JoystickDemo.h:86
JoystickDataStruct::joy_brake_valid
bool joy_brake_valid
Definition: JoystickDemo.h:91
JoystickDemo::BTN_TRUNK_CLOSE
@ BTN_TRUNK_CLOSE
Definition: JoystickDemo.h:114
JoystickDemo::timer_
ros::Timer timer_
Definition: JoystickDemo.h:98
JoystickDataStruct::door_select
int door_select
Definition: JoystickDemo.h:88
JoystickDemo::brake_gain_
float brake_gain_
Definition: JoystickDemo.h:87
JoystickDemo::AXIS_THROTTLE
@ AXIS_THROTTLE
Definition: JoystickDemo.h:117
JoystickDemo::pub_enable_
ros::Publisher pub_enable_
Definition: JoystickDemo.h:76
JoystickDemo::AXIS_DOOR_ACTION
@ AXIS_DOOR_ACTION
Definition: JoystickDemo.h:123
JoystickDemo::BTN_DRIVE
@ BTN_DRIVE
Definition: JoystickDemo.h:108
JoystickDemo::data_
JoystickDataStruct data_
Definition: JoystickDemo.h:99
JoystickDemo::last_steering_filt_output_
float last_steering_filt_output_
Definition: JoystickDemo.h:102
JoystickDemo::AXIS_COUNT_D
@ AXIS_COUNT_D
Definition: JoystickDemo.h:124
JoystickDemo::BTN_DISABLE
@ BTN_DISABLE
Definition: JoystickDemo.h:110
JoystickDemo::pub_throttle_
ros::Publisher pub_throttle_
Definition: JoystickDemo.h:72
JoystickDemo::count_
bool count_
Definition: JoystickDemo.h:93
JoystickDemo::BTN_PARK
@ BTN_PARK
Definition: JoystickDemo.h:105
JoystickDemo::cmdCallback
void cmdCallback(const ros::TimerEvent &event)
Definition: JoystickDemo.cpp:108
JoystickDemo::AXIS_COUNT_X
@ AXIS_COUNT_X
Definition: JoystickDemo.h:125
ros::Duration
node
node
JoystickDataStruct::stamp
ros::Time stamp
Definition: JoystickDemo.h:81
JoystickDemo::AXIS_BRAKE
@ AXIS_BRAKE
Definition: JoystickDemo.h:118
JoystickDataStruct::joy_throttle_valid
bool joy_throttle_valid
Definition: JoystickDemo.h:90
ros::NodeHandle
JoystickDemo::shift_
bool shift_
Definition: JoystickDemo.h:83
JoystickDemo::JoystickDemo
JoystickDemo(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: JoystickDemo.cpp:37
ros::Time::now
static Time now()


dbw_fca_joystick_demo
Author(s): Micho Radovnikovich
autogenerated on Fri Jan 5 2024 03:53:42