joy_node.cpp
Go to the documentation of this file.
1 /*
2  * teleop_pr2
3  * Copyright (c) 2009, Willow Garage, Inc.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the <ORGANIZATION> nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
30 
31 //\author: Blaise Gassend
32 
33 #include <unistd.h>
34 #include <math.h>
35 #include <linux/joystick.h>
36 #include <fcntl.h>
37 #include <sys/stat.h>
38 #include <dirent.h>
40 #include "ros/ros.h"
41 #include <sensor_msgs/Joy.h>
42 
43 
45 class Joystick
46 {
47 private:
49  bool open_;
52  std::string joy_dev_;
53  std::string joy_dev_name_;
54  double deadzone_;
55  double autorepeat_rate_; // in Hz. 0 for no repeat.
56  double coalesce_interval_; // Defaults to 100 Hz rate limit.
60  double lastDiagTime_;
61 
63 
66  {
67  double now = ros::Time::now().toSec();
68  double interval = now - lastDiagTime_;
69  if (open_)
70  stat.summary(0, "OK");
71  else
72  stat.summary(2, "Joystick not open.");
73 
74  stat.add("topic", pub_.getTopic());
75  stat.add("device", joy_dev_);
76  stat.add("device name", joy_dev_name_);
77  stat.add("dead zone", deadzone_);
78  stat.add("autorepeat rate (Hz)", autorepeat_rate_);
79  stat.add("coalesce interval (s)", coalesce_interval_);
80  stat.add("recent joystick event rate (Hz)", event_count_ / interval);
81  stat.add("recent publication rate (Hz)", pub_count_ / interval);
82  stat.add("subscribers", pub_.getNumSubscribers());
83  stat.add("default trig val", default_trig_val_);
84  stat.add("sticky buttons", sticky_buttons_);
85  event_count_ = 0;
86  pub_count_ = 0;
87  lastDiagTime_ = now;
88  }
89 
93  std::string get_dev_by_joy_name(const std::string& joy_name)
94  {
95  const char path[] = "/dev/input"; // no trailing / here
96  struct dirent *entry;
97  struct stat stat_buf;
98 
99  DIR *dev_dir = opendir(path);
100  if (dev_dir == NULL)
101  {
102  ROS_ERROR("Couldn't open %s. Error %i: %s.", path, errno, strerror(errno));
103  return "";
104  }
105 
106  while ((entry = readdir(dev_dir)) != NULL)
107  {
108  // filter entries
109  if (strncmp(entry->d_name, "js", 2) != 0) // skip device if it's not a joystick
110  continue;
111  std::string current_path = std::string(path) + "/" + entry->d_name;
112  if (stat(current_path.c_str(), &stat_buf) == -1)
113  continue;
114  if (!S_ISCHR(stat_buf.st_mode)) // input devices are character devices, skip other
115  continue;
116 
117  // get joystick name
118  int joy_fd = open(current_path.c_str(), O_RDONLY);
119  if (joy_fd == -1)
120  continue;
121 
122  char current_joy_name[128];
123  if (ioctl(joy_fd, JSIOCGNAME(sizeof(current_joy_name)), current_joy_name) < 0)
124  strncpy(current_joy_name, "Unknown", sizeof(current_joy_name));
125 
126  close(joy_fd);
127 
128  ROS_INFO("Found joystick: %s (%s).", current_joy_name, current_path.c_str());
129 
130  if (strcmp(current_joy_name, joy_name.c_str()) == 0)
131  {
132  closedir(dev_dir);
133  return current_path;
134  }
135  }
136 
137  closedir(dev_dir);
138  return "";
139  }
140 
141 public:
142  Joystick() : nh_(), diagnostic_()
143  {}
144 
146  int main(int argc, char **argv)
147  {
148  diagnostic_.add("Joystick Driver Status", this, &Joystick::diagnostics);
149  diagnostic_.setHardwareID("none");
150 
151  // Parameters
152  ros::NodeHandle nh_param("~");
153  pub_ = nh_.advertise<sensor_msgs::Joy>("joy", 1);
154  nh_param.param<std::string>("dev", joy_dev_, "/dev/input/js0");
155  nh_param.param<std::string>("dev_name", joy_dev_name_, "");
156  nh_param.param<double>("deadzone", deadzone_, 0.05);
157  nh_param.param<double>("autorepeat_rate", autorepeat_rate_, 0);
158  nh_param.param<double>("coalesce_interval", coalesce_interval_, 0.001);
159  nh_param.param<bool>("default_trig_val",default_trig_val_,false);
160  nh_param.param<bool>("sticky_buttons", sticky_buttons_, false);
161 
162  // Checks on parameters
163  if (!joy_dev_name_.empty())
164  {
165  std::string joy_dev_path = get_dev_by_joy_name(joy_dev_name_);
166  if (joy_dev_path.empty())
167  ROS_ERROR("Couldn't find a joystick with name %s. Falling back to default device.", joy_dev_name_.c_str());
168  else
169  {
170  ROS_INFO("Using %s as joystick device.", joy_dev_path.c_str());
171  joy_dev_ = joy_dev_path;
172  }
173  }
174 
175  if (autorepeat_rate_ > 1 / coalesce_interval_)
176  ROS_WARN("joy_node: autorepeat_rate (%f Hz) > 1/coalesce_interval (%f Hz) does not make sense. Timing behavior is not well defined.", autorepeat_rate_, 1/coalesce_interval_);
177 
178  if (deadzone_ >= 1)
179  {
180  ROS_WARN("joy_node: deadzone greater than 1 was requested. The semantics of deadzone have changed. It is now related to the range [-1:1] instead of [-32767:32767]. For now I am dividing your deadzone by 32767, but this behavior is deprecated so you need to update your launch file.");
181  deadzone_ /= 32767;
182  }
183 
184  if (deadzone_ > 0.9)
185  {
186  ROS_WARN("joy_node: deadzone (%f) greater than 0.9, setting it to 0.9", deadzone_);
187  deadzone_ = 0.9;
188  }
189 
190  if (deadzone_ < 0)
191  {
192  ROS_WARN("joy_node: deadzone_ (%f) less than 0, setting to 0.", deadzone_);
193  deadzone_ = 0;
194  }
195 
196  if (autorepeat_rate_ < 0)
197  {
198  ROS_WARN("joy_node: autorepeat_rate (%f) less than 0, setting to 0.", autorepeat_rate_);
199  autorepeat_rate_ = 0;
200  }
201 
202  if (coalesce_interval_ < 0)
203  {
204  ROS_WARN("joy_node: coalesce_interval (%f) less than 0, setting to 0.", coalesce_interval_);
205  coalesce_interval_ = 0;
206  }
207 
208  // Parameter conversions
209  double autorepeat_interval = 1 / autorepeat_rate_;
210  double scale = -1. / (1. - deadzone_) / 32767.;
211  double unscaled_deadzone = 32767. * deadzone_;
212 
213  js_event event;
214  struct timeval tv;
215  fd_set set;
216  int joy_fd;
217  event_count_ = 0;
218  pub_count_ = 0;
219  lastDiagTime_ = ros::Time::now().toSec();
220 
221  // Big while loop opens, publishes
222  while (nh_.ok())
223  {
224  open_ = false;
225  diagnostic_.force_update();
226  bool first_fault = true;
227  while (true)
228  {
229  ros::spinOnce();
230  if (!nh_.ok())
231  goto cleanup;
232  joy_fd = open(joy_dev_.c_str(), O_RDONLY);
233  if (joy_fd != -1)
234  {
235  // There seems to be a bug in the driver or something where the
236  // initial events that are to define the initial state of the
237  // joystick are not the values of the joystick when it was opened
238  // but rather the values of the joystick when it was last closed.
239  // Opening then closing and opening again is a hack to get more
240  // accurate initial state data.
241  close(joy_fd);
242  joy_fd = open(joy_dev_.c_str(), O_RDONLY);
243  }
244  if (joy_fd != -1)
245  break;
246  if (first_fault)
247  {
248  ROS_ERROR("Couldn't open joystick %s. Will retry every second.", joy_dev_.c_str());
249  first_fault = false;
250  }
251  sleep(1.0);
252  diagnostic_.update();
253  }
254 
255  ROS_INFO("Opened joystick: %s. deadzone_: %f.", joy_dev_.c_str(), deadzone_);
256  open_ = true;
257  diagnostic_.force_update();
258 
259  bool tv_set = false;
260  bool publication_pending = false;
261  tv.tv_sec = 1;
262  tv.tv_usec = 0;
263  sensor_msgs::Joy joy_msg; // Here because we want to reset it on device close.
264  double val; //Temporary variable to hold event values
265  sensor_msgs::Joy last_published_joy_msg; // used for sticky buttons option
266  sensor_msgs::Joy sticky_buttons_joy_msg; // used for sticky buttons option
267  while (nh_.ok())
268  {
269  ros::spinOnce();
270 
271  bool publish_now = false;
272  bool publish_soon = false;
273  FD_ZERO(&set);
274  FD_SET(joy_fd, &set);
275 
276  //ROS_INFO("Select...");
277  int select_out = select(joy_fd+1, &set, NULL, NULL, &tv);
278  //ROS_INFO("Tick...");
279  if (select_out == -1)
280  {
281  tv.tv_sec = 0;
282  tv.tv_usec = 0;
283  //ROS_INFO("Select returned negative. %i", ros::isShuttingDown());
284  continue;
285  //break; // Joystick is probably closed. Not sure if this case is useful.
286  }
287 
288  if (FD_ISSET(joy_fd, &set))
289  {
290  if (read(joy_fd, &event, sizeof(js_event)) == -1 && errno != EAGAIN)
291  break; // Joystick is probably closed. Definitely occurs.
292 
293  //ROS_INFO("Read data...");
294  joy_msg.header.stamp = ros::Time().now();
295  event_count_++;
296  switch(event.type)
297  {
298  case JS_EVENT_BUTTON:
299  case JS_EVENT_BUTTON | JS_EVENT_INIT:
300  if(event.number >= joy_msg.buttons.size())
301  {
302  int old_size = joy_msg.buttons.size();
303  joy_msg.buttons.resize(event.number+1);
304  last_published_joy_msg.buttons.resize(event.number+1);
305  sticky_buttons_joy_msg.buttons.resize(event.number+1);
306  for(unsigned int i=old_size;i<joy_msg.buttons.size();i++){
307  joy_msg.buttons[i] = 0.0;
308  last_published_joy_msg.buttons[i] = 0.0;
309  sticky_buttons_joy_msg.buttons[i] = 0.0;
310  }
311  }
312  joy_msg.buttons[event.number] = (event.value ? 1 : 0);
313  // For initial events, wait a bit before sending to try to catch
314  // all the initial events.
315  if (!(event.type & JS_EVENT_INIT))
316  publish_now = true;
317  else
318  publish_soon = true;
319  break;
320  case JS_EVENT_AXIS:
321  case JS_EVENT_AXIS | JS_EVENT_INIT:
322  val = event.value;
323  if(event.number >= joy_msg.axes.size())
324  {
325  int old_size = joy_msg.axes.size();
326  joy_msg.axes.resize(event.number+1);
327  last_published_joy_msg.axes.resize(event.number+1);
328  sticky_buttons_joy_msg.axes.resize(event.number+1);
329  for(unsigned int i=old_size;i<joy_msg.axes.size();i++){
330  joy_msg.axes[i] = 0.0;
331  last_published_joy_msg.axes[i] = 0.0;
332  sticky_buttons_joy_msg.axes[i] = 0.0;
333  }
334  }
335  if(default_trig_val_){
336  // Allows deadzone to be "smooth"
337  if (val > unscaled_deadzone)
338  val -= unscaled_deadzone;
339  else if (val < -unscaled_deadzone)
340  val += unscaled_deadzone;
341  else
342  val = 0;
343  joy_msg.axes[event.number] = val * scale;
344  // Will wait a bit before sending to try to combine events.
345  publish_soon = true;
346  break;
347  }
348  else
349  {
350  if (!(event.type & JS_EVENT_INIT))
351  {
352  val = event.value;
353  if(val > unscaled_deadzone)
354  val -= unscaled_deadzone;
355  else if(val < -unscaled_deadzone)
356  val += unscaled_deadzone;
357  else
358  val=0;
359  joy_msg.axes[event.number]= val * scale;
360  }
361 
362  publish_soon = true;
363  break;
364  default:
365  ROS_WARN("joy_node: Unknown event type. Please file a ticket. time=%u, value=%d, type=%Xh, number=%d", event.time, event.value, event.type, event.number);
366  break;
367  }
368  }
369  }
370  else if (tv_set) // Assume that the timer has expired.
371  publish_now = true;
372 
373  if (publish_now) {
374  // Assume that all the JS_EVENT_INIT messages have arrived already.
375  // This should be the case as the kernel sends them along as soon as
376  // the device opens.
377  //ROS_INFO("Publish...");
378  if (sticky_buttons_ == true) {
379  // cycle through buttons
380  for (size_t i = 0; i < joy_msg.buttons.size(); i++) {
381  // change button state only on transition from 0 to 1
382  if (joy_msg.buttons[i] == 1 && last_published_joy_msg.buttons[i] == 0) {
383  sticky_buttons_joy_msg.buttons[i] = sticky_buttons_joy_msg.buttons[i] ? 0 : 1;
384  } else {
385  // do not change the message sate
386  //sticky_buttons_joy_msg.buttons[i] = sticky_buttons_joy_msg.buttons[i] ? 0 : 1;
387  }
388  }
389  // update last published message
390  last_published_joy_msg = joy_msg;
391  // fill rest of sticky_buttons_joy_msg (time stamps, axes, etc)
392  sticky_buttons_joy_msg.header.stamp.nsec = joy_msg.header.stamp.nsec;
393  sticky_buttons_joy_msg.header.stamp.sec = joy_msg.header.stamp.sec;
394  sticky_buttons_joy_msg.header.frame_id = joy_msg.header.frame_id;
395  for(size_t i=0; i < joy_msg.axes.size(); i++){
396  sticky_buttons_joy_msg.axes[i] = joy_msg.axes[i];
397  }
398  pub_.publish(sticky_buttons_joy_msg);
399  } else {
400  pub_.publish(joy_msg);
401  }
402 
403  publish_now = false;
404  tv_set = false;
405  publication_pending = false;
406  publish_soon = false;
407  pub_count_++;
408  }
409 
410  // If an axis event occurred, start a timer to combine with other
411  // events.
412  if (!publication_pending && publish_soon)
413  {
414  tv.tv_sec = trunc(coalesce_interval_);
415  tv.tv_usec = (coalesce_interval_ - tv.tv_sec) * 1e6;
416  publication_pending = true;
417  tv_set = true;
418  //ROS_INFO("Pub pending...");
419  }
420 
421  // If nothing is going on, start a timer to do autorepeat.
422  if (!tv_set && autorepeat_rate_ > 0)
423  {
424  tv.tv_sec = trunc(autorepeat_interval);
425  tv.tv_usec = (autorepeat_interval - tv.tv_sec) * 1e6;
426  tv_set = true;
427  //ROS_INFO("Autorepeat pending... %li %li", tv.tv_sec, tv.tv_usec);
428  }
429 
430  if (!tv_set)
431  {
432  tv.tv_sec = 1;
433  tv.tv_usec = 0;
434  }
435 
436  diagnostic_.update();
437  } // End of joystick open loop.
438 
439  close(joy_fd);
440  ros::spinOnce();
441  if (nh_.ok())
442  ROS_ERROR("Connection to joystick device lost unexpectedly. Will reopen.");
443  }
444 
445  cleanup:
446  ROS_INFO("joy_node shut down.");
447 
448  return 0;
449  }
450 };
451 
452 int main(int argc, char **argv)
453 {
454  ros::init(argc, argv, "joy_node");
455  Joystick j;
456  return j.main(argc, argv);
457 }
bool default_trig_val_
Definition: joy_node.cpp:51
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
void setHardwareID(const std::string &hwid)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool open_
Definition: joy_node.cpp:49
void add(const std::string &name, TaskFunction f)
#define ROS_WARN(...)
std::string get_dev_by_joy_name(const std::string &joy_name)
Returns the device path of the first joystick that matches joy_name. If no match is found...
Definition: joy_node.cpp:93
int main(int argc, char **argv)
Opens joystick port, reads from port and publishes while node is active.
Definition: joy_node.cpp:146
double deadzone_
Definition: joy_node.cpp:54
std::string joy_dev_
Definition: joy_node.cpp:52
double coalesce_interval_
Definition: joy_node.cpp:56
int pub_count_
Definition: joy_node.cpp:58
int event_count_
Definition: joy_node.cpp:57
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::Publisher pub_
Definition: joy_node.cpp:59
double lastDiagTime_
Definition: joy_node.cpp:60
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double autorepeat_rate_
Definition: joy_node.cpp:55
Opens, reads from and publishes joystick events.
Definition: joy_node.cpp:45
bool sticky_buttons_
Definition: joy_node.cpp:50
ros::NodeHandle nh_
Definition: joy_node.cpp:48
uint32_t getNumSubscribers() const
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Publishes diagnostics and status.
Definition: joy_node.cpp:65
static Time now()
std::string getTopic() const
bool ok() const
void add(const std::string &key, const T &val)
std::string joy_dev_name_
Definition: joy_node.cpp:53
ROSCPP_DECL void spinOnce()
diagnostic_updater::Updater diagnostic_
Definition: joy_node.cpp:62
#define ROS_ERROR(...)


joy
Author(s): Morgan Quigley, Brian Gerkey, Kevin Watts, Blaise Gassend
autogenerated on Mon Jun 10 2019 13:42:39