joy_node.cpp
Go to the documentation of this file.
1 /*
2  * joy_node
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 <string>
34 
35 #include <dirent.h>
36 #include <fcntl.h>
37 #include <linux/input.h>
38 #include <linux/joystick.h>
39 #include <math.h>
40 #include <sys/stat.h>
41 #include <unistd.h>
42 
44 #include <ros/ros.h>
45 #include <sensor_msgs/Joy.h>
46 #include <sensor_msgs/JoyFeedbackArray.h>
47 
48 
50 class Joystick
51 {
52 private:
54  bool open_;
57  std::string joy_dev_;
58  std::string joy_dev_name_;
59  std::string joy_dev_ff_;
60  double deadzone_;
61  double autorepeat_rate_; // in Hz. 0 for no repeat.
62  double coalesce_interval_; // Defaults to 100 Hz rate limit.
66  double lastDiagTime_;
67 
68  int ff_fd_;
69  struct ff_effect joy_effect_;
71 
73 
76  {
77  double now = ros::Time::now().toSec();
78  double interval = now - lastDiagTime_;
79  if (open_)
80  {
81  stat.summary(0, "OK");
82  }
83  else
84  {
85  stat.summary(2, "Joystick not open.");
86  }
87 
88  stat.add("topic", pub_.getTopic());
89  stat.add("device", joy_dev_);
90  stat.add("device name", joy_dev_name_);
91  stat.add("dead zone", deadzone_);
92  stat.add("autorepeat rate (Hz)", autorepeat_rate_);
93  stat.add("coalesce interval (s)", coalesce_interval_);
94  stat.add("recent joystick event rate (Hz)", event_count_ / interval);
95  stat.add("recent publication rate (Hz)", pub_count_ / interval);
96  stat.add("subscribers", pub_.getNumSubscribers());
97  stat.add("default trig val", default_trig_val_);
98  stat.add("sticky buttons", sticky_buttons_);
99  event_count_ = 0;
100  pub_count_ = 0;
101  lastDiagTime_ = now;
102  }
103 
107  std::string get_dev_by_joy_name(const std::string& joy_name)
108  {
109  const char path[] = "/dev/input"; // no trailing / here
110  struct dirent *entry;
111  struct stat stat_buf;
112 
113  DIR *dev_dir = opendir(path);
114  if (dev_dir == nullptr)
115  {
116  ROS_ERROR("Couldn't open %s. Error %i: %s.", path, errno, strerror(errno));
117  return "";
118  }
119 
120  while ((entry = readdir(dev_dir)) != nullptr)
121  {
122  // filter entries
123  if (strncmp(entry->d_name, "js", 2) != 0) // skip device if it's not a joystick
124  {
125  continue;
126  }
127  std::string current_path = std::string(path) + "/" + entry->d_name;
128  if (stat(current_path.c_str(), &stat_buf) == -1)
129  {
130  continue;
131  }
132  if (!S_ISCHR(stat_buf.st_mode)) // input devices are character devices, skip other
133  {
134  continue;
135  }
136 
137  // get joystick name
138  int joy_fd = open(current_path.c_str(), O_RDONLY);
139  if (joy_fd == -1)
140  {
141  continue;
142  }
143 
144  char current_joy_name[128];
145  if (ioctl(joy_fd, JSIOCGNAME(sizeof(current_joy_name)), current_joy_name) < 0)
146  {
147  strncpy(current_joy_name, "Unknown", sizeof(current_joy_name));
148  }
149 
150  close(joy_fd);
151 
152  ROS_INFO("Found joystick: %s (%s).", current_joy_name, current_path.c_str());
153 
154  if (strcmp(current_joy_name, joy_name.c_str()) == 0)
155  {
156  closedir(dev_dir);
157  return current_path;
158  }
159  }
160 
161  closedir(dev_dir);
162  return "";
163  }
164 
165 public:
166  Joystick() : nh_(), diagnostic_(), ff_fd_(-1)
167  {}
168 
169  void set_feedback(const sensor_msgs::JoyFeedbackArray::ConstPtr& msg)
170  {
171  if (ff_fd_ == -1)
172  {
173  return; // we arent ready yet
174  }
175 
176  size_t size = msg->array.size();
177  for (size_t i = 0; i < size; i++)
178  {
179  // process each feedback
180  if (msg->array[i].type == 1 && ff_fd_ != -1) // TYPE_RUMBLE
181  {
182  // if id is zero, thats low freq, 1 is high
183  joy_effect_.direction = 0; // down
184  joy_effect_.type = FF_RUMBLE;
185  if (msg->array[i].id == 0)
186  {
187  joy_effect_.u.rumble.strong_magnitude = (static_cast<float>(0xFFFFU))*msg->array[i].intensity;
188  }
189  else
190  {
191  joy_effect_.u.rumble.weak_magnitude = (static_cast<float>(0xFFFFU))*msg->array[i].intensity;
192  }
193 
194  joy_effect_.replay.length = 1000;
195  joy_effect_.replay.delay = 0;
196 
197  update_feedback_ = true;
198  }
199  }
200  }
201 
203  int main(int argc, char **argv)
204  {
205  diagnostic_.add("Joystick Driver Status", this, &Joystick::diagnostics);
206  diagnostic_.setHardwareID("none");
207 
208  // Parameters
209  ros::NodeHandle nh_param("~");
210  pub_ = nh_.advertise<sensor_msgs::Joy>("joy", 1);
211  ros::Subscriber sub = nh_.subscribe("joy/set_feedback", 10, &Joystick::set_feedback, this);
212  nh_param.param<std::string>("dev", joy_dev_, "/dev/input/js0");
213  nh_param.param<std::string>("dev_ff", joy_dev_ff_, "/dev/input/event0");
214  nh_param.param<std::string>("dev_name", joy_dev_name_, "");
215  nh_param.param<double>("deadzone", deadzone_, 0.05);
216  nh_param.param<double>("autorepeat_rate", autorepeat_rate_, 0);
217  nh_param.param<double>("coalesce_interval", coalesce_interval_, 0.001);
218  nh_param.param<bool>("default_trig_val", default_trig_val_, false);
219  nh_param.param<bool>("sticky_buttons", sticky_buttons_, false);
220 
221  // Checks on parameters
222  if (!joy_dev_name_.empty())
223  {
224  std::string joy_dev_path = get_dev_by_joy_name(joy_dev_name_);
225  if (joy_dev_path.empty())
226  {
227  ROS_ERROR("Couldn't find a joystick with name %s. Falling back to default device.", joy_dev_name_.c_str());
228  }
229  else
230  {
231  ROS_INFO("Using %s as joystick device.", joy_dev_path.c_str());
232  joy_dev_ = joy_dev_path;
233  }
234  }
235 
236  if (autorepeat_rate_ > 1 / coalesce_interval_)
237  {
238  ROS_WARN("joy_node: autorepeat_rate (%f Hz) > 1/coalesce_interval (%f Hz) "
239  "does not make sense. Timing behavior is not well defined.", autorepeat_rate_, 1/coalesce_interval_);
240  }
241 
242  if (deadzone_ >= 1)
243  {
244  ROS_WARN("joy_node: deadzone greater than 1 was requested. The semantics of deadzone have changed. "
245  "It is now related to the range [-1:1] instead of [-32767:32767]. For now I am dividing your deadzone "
246  "by 32767, but this behavior is deprecated so you need to update your launch file.");
247  deadzone_ /= 32767;
248  }
249 
250  if (deadzone_ > 0.9)
251  {
252  ROS_WARN("joy_node: deadzone (%f) greater than 0.9, setting it to 0.9", deadzone_);
253  deadzone_ = 0.9;
254  }
255 
256  if (deadzone_ < 0)
257  {
258  ROS_WARN("joy_node: deadzone_ (%f) less than 0, setting to 0.", deadzone_);
259  deadzone_ = 0;
260  }
261 
262  if (autorepeat_rate_ < 0)
263  {
264  ROS_WARN("joy_node: autorepeat_rate (%f) less than 0, setting to 0.", autorepeat_rate_);
265  autorepeat_rate_ = 0;
266  }
267 
268  if (coalesce_interval_ < 0)
269  {
270  ROS_WARN("joy_node: coalesce_interval (%f) less than 0, setting to 0.", coalesce_interval_);
271  coalesce_interval_ = 0;
272  }
273 
274  // Parameter conversions
275  double autorepeat_interval = 1 / autorepeat_rate_;
276  double scale = -1. / (1. - deadzone_) / 32767.;
277  double unscaled_deadzone = 32767. * deadzone_;
278 
279  js_event event;
280  struct timeval tv;
281  fd_set set;
282  int joy_fd;
283  event_count_ = 0;
284  pub_count_ = 0;
285  lastDiagTime_ = ros::Time::now().toSec();
286 
287  // Big while loop opens, publishes
288  while (nh_.ok())
289  {
290  open_ = false;
291  diagnostic_.force_update();
292  bool first_fault = true;
293  while (true)
294  {
295  ros::spinOnce();
296  if (!nh_.ok())
297  {
298  goto cleanup;
299  }
300  joy_fd = open(joy_dev_.c_str(), O_RDONLY);
301  if (joy_fd != -1)
302  {
303  // There seems to be a bug in the driver or something where the
304  // initial events that are to define the initial state of the
305  // joystick are not the values of the joystick when it was opened
306  // but rather the values of the joystick when it was last closed.
307  // Opening then closing and opening again is a hack to get more
308  // accurate initial state data.
309  close(joy_fd);
310  joy_fd = open(joy_dev_.c_str(), O_RDONLY);
311  }
312  if (joy_fd != -1)
313  {
314  break;
315  }
316  if (first_fault)
317  {
318  ROS_ERROR("Couldn't open joystick %s. Will retry every second.", joy_dev_.c_str());
319  first_fault = false;
320  }
321  sleep(1.0);
322  diagnostic_.update();
323  }
324 
325  if (!joy_dev_ff_.empty())
326  {
327  ff_fd_ = open(joy_dev_ff_.c_str(), O_RDWR);
328 
329  /* Set the gain of the device*/
330  int gain = 100; /* between 0 and 100 */
331  struct input_event ie; /* structure used to communicate with the driver */
332 
333  ie.type = EV_FF;
334  ie.code = FF_GAIN;
335  ie.value = 0xFFFFUL * gain / 100;
336 
337  if (write(ff_fd_, &ie, sizeof(ie)) == -1)
338  {
339  ROS_WARN("Couldn't set gain on joystick force feedback: %s", strerror(errno));
340  }
341 
342  memset(&joy_effect_, 0, sizeof(joy_effect_));
343  joy_effect_.id = -1;
344  joy_effect_.direction = 0; // down
345  joy_effect_.type = FF_RUMBLE;
346  joy_effect_.u.rumble.strong_magnitude = 0;
347  joy_effect_.u.rumble.weak_magnitude = 0;
348  joy_effect_.replay.length = 1000;
349  joy_effect_.replay.delay = 0;
350 
351  // upload the effect
352  int ret = ioctl(ff_fd_, EVIOCSFF, &joy_effect_);
353  }
354 
355  char current_joy_name[128];
356  if (ioctl(joy_fd, JSIOCGNAME(sizeof(current_joy_name)), current_joy_name) < 0)
357  {
358  strncpy(current_joy_name, "Unknown", sizeof(current_joy_name));
359  }
360 
361  ROS_INFO("Opened joystick: %s (%s). deadzone_: %f.", joy_dev_.c_str(), current_joy_name, deadzone_);
362  open_ = true;
363  diagnostic_.force_update();
364 
365  bool tv_set = false;
366  bool publication_pending = false;
367  tv.tv_sec = 1;
368  tv.tv_usec = 0;
369  sensor_msgs::Joy joy_msg; // Here because we want to reset it on device close.
370  double val; // Temporary variable to hold event values
371  while (nh_.ok())
372  {
373  ros::spinOnce();
374 
375  bool publish_now = false;
376  bool publish_soon = false;
377  FD_ZERO(&set);
378  FD_SET(joy_fd, &set);
379 
380  int select_out = select(joy_fd+1, &set, nullptr, nullptr, &tv);
381  if (select_out == -1)
382  {
383  tv.tv_sec = 0;
384  tv.tv_usec = 0;
385  continue;
386  }
387 
388  // play the rumble effect (can probably do this at lower rate later)
389  if (ff_fd_ != -1)
390  {
391  struct input_event start;
392  start.type = EV_FF;
393  start.code = joy_effect_.id;
394  start.value = 1;
395  if (write(ff_fd_, (const void*) &start, sizeof(start)) == -1)
396  {
397  break; // fd closed
398  }
399 
400  // upload the effect
401  if (update_feedback_ == true)
402  {
403  int ret = ioctl(ff_fd_, EVIOCSFF, &joy_effect_);
404  update_feedback_ = false;
405  }
406  }
407 
408  if (FD_ISSET(joy_fd, &set))
409  {
410  if (read(joy_fd, &event, sizeof(js_event)) == -1 && errno != EAGAIN)
411  {
412  break; // Joystick is probably closed. Definitely occurs.
413  }
414 
415  joy_msg.header.stamp = ros::Time().now();
416  event_count_++;
417  switch (event.type)
418  {
419  case JS_EVENT_BUTTON:
420  case JS_EVENT_BUTTON | JS_EVENT_INIT:
421  if (event.number >= joy_msg.buttons.size())
422  {
423  size_t old_size = joy_msg.buttons.size();
424  joy_msg.buttons.resize(event.number+1);
425  for (size_t i = old_size; i < joy_msg.buttons.size(); i++)
426  {
427  joy_msg.buttons[i] = 0.0;
428  }
429  }
430  if (sticky_buttons_)
431  {
432  if (event.value == 1)
433  {
434  joy_msg.buttons[event.number] = 1 - joy_msg.buttons[event.number];
435  }
436  }
437  else
438  {
439  joy_msg.buttons[event.number] = (event.value ? 1 : 0);
440  }
441  // For initial events, wait a bit before sending to try to catch
442  // all the initial events.
443  if (!(event.type & JS_EVENT_INIT))
444  {
445  publish_now = true;
446  }
447  else
448  {
449  publish_soon = true;
450  }
451  break;
452  case JS_EVENT_AXIS:
453  case JS_EVENT_AXIS | JS_EVENT_INIT:
454  val = event.value;
455  if (event.number >= joy_msg.axes.size())
456  {
457  size_t old_size = joy_msg.axes.size();
458  joy_msg.axes.resize(event.number+1);
459  for (size_t i = old_size; i < joy_msg.axes.size(); i++)
460  {
461  joy_msg.axes[i] = 0.0;
462  }
463  }
464  if (default_trig_val_)
465  {
466  // Allows deadzone to be "smooth"
467  if (val > unscaled_deadzone)
468  {
469  val -= unscaled_deadzone;
470  }
471  else if (val < -unscaled_deadzone)
472  {
473  val += unscaled_deadzone;
474  }
475  else
476  {
477  val = 0;
478  }
479  joy_msg.axes[event.number] = val * scale;
480  // Will wait a bit before sending to try to combine events.
481  publish_soon = true;
482  break;
483  }
484  else
485  {
486  if (!(event.type & JS_EVENT_INIT))
487  {
488  val = event.value;
489  if (val > unscaled_deadzone)
490  {
491  val -= unscaled_deadzone;
492  }
493  else if (val < -unscaled_deadzone)
494  {
495  val += unscaled_deadzone;
496  }
497  else
498  {
499  val = 0;
500  }
501  joy_msg.axes[event.number] = val * scale;
502  }
503 
504  publish_soon = true;
505  break;
506  }
507  default:
508  ROS_WARN("joy_node: Unknown event type. Please file a ticket. "
509  "time=%u, value=%d, type=%Xh, number=%d", event.time, event.value, event.type, event.number);
510  break;
511  }
512  }
513  else if (tv_set) // Assume that the timer has expired.
514  {
515  joy_msg.header.stamp = ros::Time().now();
516  publish_now = true;
517  }
518 
519  if (publish_now)
520  {
521  // Assume that all the JS_EVENT_INIT messages have arrived already.
522  // This should be the case as the kernel sends them along as soon as
523  // the device opens.
524  joy_msg.header.stamp = ros::Time().now();
525  joy_msg.header.frame_id = joy_dev_.c_str();
526  pub_.publish(joy_msg);
527 
528  publish_now = false;
529  tv_set = false;
530  publication_pending = false;
531  publish_soon = false;
532  pub_count_++;
533  }
534 
535  // If an axis event occurred, start a timer to combine with other
536  // events.
537  if (!publication_pending && publish_soon)
538  {
539  tv.tv_sec = trunc(coalesce_interval_);
540  tv.tv_usec = (coalesce_interval_ - tv.tv_sec) * 1e6;
541  publication_pending = true;
542  tv_set = true;
543  }
544 
545  // If nothing is going on, start a timer to do autorepeat.
546  if (!tv_set && autorepeat_rate_ > 0)
547  {
548  tv.tv_sec = trunc(autorepeat_interval);
549  tv.tv_usec = (autorepeat_interval - tv.tv_sec) * 1e6;
550  tv_set = true;
551  }
552 
553  if (!tv_set)
554  {
555  tv.tv_sec = 1;
556  tv.tv_usec = 0;
557  }
558 
559  diagnostic_.update();
560  } // End of joystick open loop.
561 
562  close(ff_fd_);
563  close(joy_fd);
564  ros::spinOnce();
565  if (nh_.ok())
566  {
567  ROS_ERROR("Connection to joystick device lost unexpectedly. Will reopen.");
568  }
569  }
570 
571  cleanup:
572  ROS_INFO("joy_node shut down.");
573 
574  return 0;
575  }
576 };
577 
578 int main(int argc, char **argv)
579 {
580  ros::init(argc, argv, "joy_node");
581  Joystick j;
582  return j.main(argc, argv);
583 }
bool update_feedback_
Definition: joy_node.cpp:70
bool default_trig_val_
Definition: joy_node.cpp:56
void summary(unsigned char lvl, const std::string s)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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:54
void add(const std::string &name, TaskFunction f)
void set_feedback(const sensor_msgs::JoyFeedbackArray::ConstPtr &msg)
Definition: joy_node.cpp:169
#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:107
int main(int argc, char **argv)
Opens joystick port, reads from port and publishes while node is active.
Definition: joy_node.cpp:203
int ff_fd_
Definition: joy_node.cpp:68
std::string joy_dev_ff_
Definition: joy_node.cpp:59
double deadzone_
Definition: joy_node.cpp:60
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
std::string joy_dev_
Definition: joy_node.cpp:57
double coalesce_interval_
Definition: joy_node.cpp:62
int pub_count_
Definition: joy_node.cpp:64
int event_count_
Definition: joy_node.cpp:63
#define ROS_INFO(...)
ros::Publisher pub_
Definition: joy_node.cpp:65
double lastDiagTime_
Definition: joy_node.cpp:66
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double autorepeat_rate_
Definition: joy_node.cpp:61
Opens, reads from and publishes joystick events.
Definition: joy_node.cpp:50
struct ff_effect joy_effect_
Definition: joy_node.cpp:69
bool sticky_buttons_
Definition: joy_node.cpp:55
std::string getTopic() const
ros::NodeHandle nh_
Definition: joy_node.cpp:53
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Publishes diagnostics and status.
Definition: joy_node.cpp:75
static Time now()
void add(const std::string &key, const T &val)
std::string joy_dev_name_
Definition: joy_node.cpp:58
uint32_t getNumSubscribers() const
ROSCPP_DECL void spinOnce()
bool ok() const
diagnostic_updater::Updater diagnostic_
Definition: joy_node.cpp:72
#define ROS_ERROR(...)


joy
Author(s): Morgan Quigley, Brian Gerkey, Kevin Watts, Blaise Gassend
autogenerated on Mon Feb 28 2022 22:37:01