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


joy
Author(s): Morgan Quigley, Brian Gerkey, Kevin Watts, Blaise Gassend
autogenerated on Wed Sep 20 2023 02:17:01