JoystickDemo.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, 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  priv_nh.getParam("brake", brake_);
47  priv_nh.getParam("throttle", throttle_);
48  priv_nh.getParam("steer", steer_);
49  priv_nh.getParam("shift", shift_);
50 
51  brake_gain_ = 1.0;
52  throttle_gain_ = 1.0;
53  priv_nh.getParam("brake_gain", brake_gain_);
54  priv_nh.getParam("throttle_gain", throttle_gain_);
55  brake_gain_ = std::min(std::max(brake_gain_, (float)0), (float)1);
56  throttle_gain_ = std::min(std::max(throttle_gain_, (float)0), (float)1);
57 
58  ignore_ = false;
59  enable_ = true;
60  count_ = false;
61  strq_ = false;
62  svel_ = 0.0;
64  priv_nh.getParam("ignore", ignore_);
65  priv_nh.getParam("enable", enable_);
66  priv_nh.getParam("count", count_);
67  priv_nh.getParam("strq", strq_);
68  priv_nh.getParam("svel", svel_);
69 
70  sub_joy_ = node.subscribe("/joy", 1, &JoystickDemo::recvJoy, this);
71 
72  data_.brake_joy = 0.0;
73  data_.gear_cmd = dbw_polaris_msgs::Gear::NONE;
74  data_.steering_joy = 0.0;
75  data_.steering_mult = false;
76  data_.steering_cal = false;
77  data_.throttle_joy = 0.0;
78  data_.joy_throttle_valid = false;
79  data_.joy_brake_valid = false;
80 
81  if (brake_) {
82  pub_brake_ = node.advertise<dbw_polaris_msgs::BrakeCmd>("brake_cmd", 1);
83  }
84  if (throttle_) {
85  pub_throttle_ = node.advertise<dbw_polaris_msgs::ThrottleCmd>("throttle_cmd", 1);
86  }
87  if (steer_) {
88  pub_steering_ = node.advertise<dbw_polaris_msgs::SteeringCmd>("steering_cmd", 1);
89  }
90  if (shift_) {
91  pub_gear_ = node.advertise<dbw_polaris_msgs::GearCmd>("gear_cmd", 1);
92  }
93  if (enable_) {
94  pub_enable_ = node.advertise<std_msgs::Empty>("enable", 1);
95  pub_disable_ = node.advertise<std_msgs::Empty>("disable", 1);
96  }
97 
99 }
100 
102 {
103  // Detect joy timeouts and reset
104  if (event.current_real - data_.stamp > ros::Duration(0.1)) {
105  data_.joy_throttle_valid = false;
106  data_.joy_brake_valid = false;
108  return;
109  }
110 
111  // Optional watchdog counter
112  if (count_) {
113  counter_++;
114  }
115 
116  // Brake
117  if (brake_) {
118  dbw_polaris_msgs::BrakeCmd msg;
119  msg.enable = true;
120  msg.ignore = ignore_;
121  msg.count = counter_;
122  msg.pedal_cmd_type = dbw_polaris_msgs::BrakeCmd::CMD_PERCENT;
123  msg.pedal_cmd = data_.brake_joy * brake_gain_;
125  }
126 
127  // Throttle
128  if (throttle_) {
129  dbw_polaris_msgs::ThrottleCmd msg;
130  msg.enable = true;
131  msg.ignore = ignore_;
132  msg.count = counter_;
133  msg.pedal_cmd_type = dbw_polaris_msgs::ThrottleCmd::CMD_PERCENT;
134  msg.pedal_cmd = data_.throttle_joy * throttle_gain_;
136  }
137 
138  // Steering
139  if (steer_) {
140  dbw_polaris_msgs::SteeringCmd msg;
141  msg.enable = true;
142  msg.ignore = ignore_;
143  msg.count = counter_;
144  msg.calibrate = data_.steering_cal;
145  if (!strq_) {
146  msg.cmd_type = dbw_polaris_msgs::SteeringCmd::CMD_ANGLE;
147 
148  float raw_steering_cmd;
149  if (data_.steering_mult) {
150  raw_steering_cmd = dbw_polaris_msgs::SteeringCmd::ANGLE_MAX * data_.steering_joy;
151  } else {
152  raw_steering_cmd = 0.5 * dbw_polaris_msgs::SteeringCmd::ANGLE_MAX * data_.steering_joy;
153  }
154 
155  float tau = 0.1;
156  float filtered_steering_cmd = 0.02 / tau * raw_steering_cmd + (1 - 0.02 / tau) * last_steering_filt_output_;
157  last_steering_filt_output_ = filtered_steering_cmd;
158 
159  msg.steering_wheel_angle_velocity = svel_;
160  msg.steering_wheel_angle_cmd = filtered_steering_cmd;
161  } else {
162  msg.cmd_type = dbw_polaris_msgs::SteeringCmd::CMD_TORQUE;
163  msg.steering_wheel_torque_cmd = dbw_polaris_msgs::SteeringCmd::TORQUE_MAX * data_.steering_joy;
164  }
166  }
167 
168  // Gear
169  if (shift_) {
170  if (data_.gear_cmd != dbw_polaris_msgs::Gear::NONE) {
171  dbw_polaris_msgs::GearCmd msg;
172  msg.cmd.gear = data_.gear_cmd;
174  }
175  }
176 }
177 
178 void JoystickDemo::recvJoy(const sensor_msgs::Joy::ConstPtr& msg)
179 {
180  // Check for expected sizes
181  if (msg->axes.size() != (size_t)AXIS_COUNT_X && msg->buttons.size() != (size_t)BTN_COUNT_X) {
182  if (msg->axes.size() == (size_t)AXIS_COUNT_D && msg->buttons.size() == (size_t)BTN_COUNT_D) {
183  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.");
184  }
185  if (msg->axes.size() != (size_t)AXIS_COUNT_X) {
186  ROS_ERROR_THROTTLE(2.0, "Expected %zu joy axis count, received %zu", (size_t)AXIS_COUNT_X, msg->axes.size());
187  }
188  if (msg->buttons.size() != (size_t)BTN_COUNT_X) {
189  ROS_ERROR_THROTTLE(2.0, "Expected %zu joy button count, received %zu", (size_t)BTN_COUNT_X, msg->buttons.size());
190  }
191  return;
192  }
193 
194  // Handle joystick startup
195  if (msg->axes[AXIS_THROTTLE] != 0.0) {
196  data_.joy_throttle_valid = true;
197  }
198  if (msg->axes[AXIS_BRAKE] != 0.0) {
199  data_.joy_brake_valid = true;
200  }
201 
202  // Throttle
204  data_.throttle_joy = 0.5 - 0.5 * msg->axes[AXIS_THROTTLE];
205  }
206 
207  // Brake
208  if (data_.joy_brake_valid) {
209  data_.brake_joy = 0.5 - 0.5 * msg->axes[AXIS_BRAKE];
210  }
211 
212  // Gear
213  if (msg->buttons[BTN_PARK]) {
214  data_.gear_cmd = dbw_polaris_msgs::Gear::PARK;
215  } else if (msg->buttons[BTN_REVERSE]) {
216  data_.gear_cmd = dbw_polaris_msgs::Gear::REVERSE;
217  } else if (msg->buttons[BTN_DRIVE]) {
218  data_.gear_cmd = dbw_polaris_msgs::Gear::DRIVE;
219  } else if (msg->buttons[BTN_NEUTRAL]) {
220  data_.gear_cmd = dbw_polaris_msgs::Gear::NEUTRAL;
221  } else {
222  data_.gear_cmd = dbw_polaris_msgs::Gear::NONE;
223  }
224 
225  // Steering
226  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];
227  data_.steering_mult = msg->buttons[BTN_STEER_MULT_1] || msg->buttons[BTN_STEER_MULT_2];
228  data_.steering_cal = msg->buttons[BTN_STEER_MULT_1] && msg->buttons[BTN_STEER_MULT_2];
229 
230  // Optional enable and disable buttons
231  if (enable_) {
232  if (msg->buttons[BTN_ENABLE]) {
233  pub_enable_.publish(std_msgs::Empty());
234  }
235  if (msg->buttons[BTN_DISABLE]) {
236  pub_disable_.publish(std_msgs::Empty());
237  }
238  }
239 
241  joy_ = *msg;
242 }
243 
ROS_ERROR_THROTTLE
#define ROS_ERROR_THROTTLE(period,...)
JoystickDemo::strq_
bool strq_
Definition: JoystickDemo.h:89
JoystickDemo::BTN_STEER_MULT_2
@ BTN_STEER_MULT_2
Definition: JoystickDemo.h:107
JoystickDemo::BTN_STEER_MULT_1
@ BTN_STEER_MULT_1
Definition: JoystickDemo.h:106
JoystickDemo::throttle_gain_
float throttle_gain_
Definition: JoystickDemo.h:83
msg
msg
JoystickDemo::pub_gear_
ros::Publisher pub_gear_
Definition: JoystickDemo.h:71
JoystickDemo::steer_
bool steer_
Definition: JoystickDemo.h:78
JoystickDemo::BTN_COUNT_X
@ BTN_COUNT_X
Definition: JoystickDemo.h:110
JoystickDemo.h
JoystickDemo::pub_disable_
ros::Publisher pub_disable_
Definition: JoystickDemo.h:73
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
JoystickDataStruct::steering_cal
bool steering_cal
Definition: JoystickDemo.h:86
JoystickDemo::AXIS_STEER_2
@ AXIS_STEER_2
Definition: JoystickDemo.h:115
JoystickDemo::BTN_COUNT_D
@ BTN_COUNT_D
Definition: JoystickDemo.h:111
JoystickDemo::pub_brake_
ros::Publisher pub_brake_
Definition: JoystickDemo.h:68
JoystickDemo::throttle_
bool throttle_
Definition: JoystickDemo.h:77
JoystickDemo::BTN_REVERSE
@ BTN_REVERSE
Definition: JoystickDemo.h:101
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
JoystickDemo::BTN_ENABLE
@ BTN_ENABLE
Definition: JoystickDemo.h:104
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
JoystickDemo::ignore_
bool ignore_
Definition: JoystickDemo.h:86
JoystickDemo::BTN_NEUTRAL
@ BTN_NEUTRAL
Definition: JoystickDemo.h:102
JoystickDataStruct::steering_mult
bool steering_mult
Definition: JoystickDemo.h:84
JoystickDemo::joy_
sensor_msgs::Joy joy_
Definition: JoystickDemo.h:95
JoystickDemo::counter_
uint8_t counter_
Definition: JoystickDemo.h:96
JoystickDemo::pub_steering_
ros::Publisher pub_steering_
Definition: JoystickDemo.h:70
JoystickDemo::sub_joy_
ros::Subscriber sub_joy_
Definition: JoystickDemo.h:67
JoystickDemo::enable_
bool enable_
Definition: JoystickDemo.h:87
JoystickDataStruct::steering_joy
float steering_joy
Definition: JoystickDemo.h:83
JoystickDemo::recvJoy
void recvJoy(const sensor_msgs::Joy::ConstPtr &msg)
Definition: JoystickDemo.cpp:178
JoystickDataStruct::brake_joy
float brake_joy
Definition: JoystickDemo.h:81
JoystickDemo::AXIS_STEER_1
@ AXIS_STEER_1
Definition: JoystickDemo.h:114
JoystickDataStruct::throttle_joy
float throttle_joy
Definition: JoystickDemo.h:82
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
JoystickDemo::brake_
bool brake_
Definition: JoystickDemo.h:76
ros::TimerEvent
ros::TimerEvent::current_real
Time current_real
JoystickDemo::svel_
float svel_
Definition: JoystickDemo.h:90
JoystickDataStruct::gear_cmd
int gear_cmd
Definition: JoystickDemo.h:85
JoystickDataStruct::joy_brake_valid
bool joy_brake_valid
Definition: JoystickDemo.h:88
JoystickDemo::timer_
ros::Timer timer_
Definition: JoystickDemo.h:93
JoystickDemo::brake_gain_
float brake_gain_
Definition: JoystickDemo.h:82
JoystickDemo::AXIS_THROTTLE
@ AXIS_THROTTLE
Definition: JoystickDemo.h:112
JoystickDemo::pub_enable_
ros::Publisher pub_enable_
Definition: JoystickDemo.h:72
JoystickDemo::BTN_DRIVE
@ BTN_DRIVE
Definition: JoystickDemo.h:103
JoystickDemo::data_
JoystickDataStruct data_
Definition: JoystickDemo.h:94
JoystickDemo::last_steering_filt_output_
float last_steering_filt_output_
Definition: JoystickDemo.h:97
JoystickDemo::AXIS_COUNT_D
@ AXIS_COUNT_D
Definition: JoystickDemo.h:119
JoystickDemo::BTN_DISABLE
@ BTN_DISABLE
Definition: JoystickDemo.h:105
JoystickDemo::pub_throttle_
ros::Publisher pub_throttle_
Definition: JoystickDemo.h:69
JoystickDemo::count_
bool count_
Definition: JoystickDemo.h:88
JoystickDemo::BTN_PARK
@ BTN_PARK
Definition: JoystickDemo.h:100
JoystickDemo::cmdCallback
void cmdCallback(const ros::TimerEvent &event)
Definition: JoystickDemo.cpp:101
JoystickDemo::AXIS_COUNT_X
@ AXIS_COUNT_X
Definition: JoystickDemo.h:120
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
JoystickDataStruct::stamp
ros::Time stamp
Definition: JoystickDemo.h:80
JoystickDemo::AXIS_BRAKE
@ AXIS_BRAKE
Definition: JoystickDemo.h:113
JoystickDataStruct::joy_throttle_valid
bool joy_throttle_valid
Definition: JoystickDemo.h:87
ros::NodeHandle
JoystickDemo::shift_
bool shift_
Definition: JoystickDemo.h:79
JoystickDemo::JoystickDemo
JoystickDemo(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: JoystickDemo.cpp:37
ros::Time::now
static Time now()


dbw_polaris_joystick_demo
Author(s): Micho Radovnikovich
autogenerated on Thu Jan 4 2024 03:36:20