39 #include <linux/input.h>
40 #include <linux/joystick.h>
47 #include <sensor_msgs/Joy.h>
48 #include <sensor_msgs/JoyFeedbackArray.h>
84 typedef std::unique_ptr<DIR, decltype(&closedir)>
dir_ptr;
97 stat.
summary(2,
"Joystick not open.");
107 stat.
add(
"recent publication rate (Hz)",
pub_count_ / interval);
121 const char path[] =
"/dev/input";
122 struct dirent *entry;
123 struct stat stat_buf;
126 if (dev_dir ==
nullptr)
128 ROS_ERROR(
"Couldn't open %s. Error %i: %s.", path, errno, strerror(errno));
132 while ((entry = readdir(dev_dir.get())) !=
nullptr)
135 if (strncmp(entry->d_name,
"js", 2) != 0)
139 std::string current_path = std::string(path) +
"/" + entry->d_name;
140 if (stat(current_path.c_str(), &stat_buf) == -1)
144 if (!S_ISCHR(stat_buf.st_mode))
150 int joy_fd = open(current_path.c_str(), O_RDONLY);
156 char current_joy_name[128];
157 if (ioctl(joy_fd, JSIOCGNAME(
sizeof(current_joy_name)), current_joy_name) < 0)
159 strncpy(current_joy_name,
"Unknown",
sizeof(current_joy_name));
164 ROS_INFO(
"Found joystick: %s (%s).", current_joy_name, current_path.c_str());
166 if (strcmp(current_joy_name, joy_name.c_str()) == 0)
181 const char path[] =
"/dev/input/by-id";
182 struct dirent *entry;
185 char realpath_buf[PATH_MAX];
186 char *res = realpath(joy_dev.c_str(), realpath_buf);
193 if (dev_dir ==
nullptr)
195 ROS_ERROR(
"Couldn't open %s. Error %i: %s.", path, errno, strerror(errno));
199 const std::string joy_dev_real(realpath_buf);
200 std::string joy_dev_id;
205 while ((entry = readdir(dev_dir.get())) !=
nullptr)
207 res = strstr(entry->d_name,
"-joystick");
214 const auto current_path = std::string(path) +
"/" + entry->d_name;
215 res = realpath(current_path.c_str(), realpath_buf);
221 const std::string dev_real(realpath_buf);
222 if (dev_real == joy_dev_real)
225 joy_dev_id = current_path;
231 if (joy_dev_id.empty())
236 const auto joy_dev_id_prefix = joy_dev_id.substr(0, joy_dev_id.length() - strlen(
"-joystick"));
237 std::string event_dev;
242 while ((entry = readdir(dev_dir.get())) !=
nullptr)
244 res = strstr(entry->d_name,
"-event-joystick");
250 const auto current_path = std::string(path) +
"/" + entry->d_name;
251 if (current_path.find(joy_dev_id_prefix) != std::string::npos)
253 ROS_INFO(
"Found force feedback event device %s", current_path.c_str());
254 event_dev = current_path;
273 size_t size =
msg->array.size();
274 for (
size_t i = 0; i < size; i++)
277 if (
msg->array[i].type == 1 &&
ff_fd_ != -1)
282 if (
msg->array[i].id == 0)
284 joy_effect_.u.rumble.strong_magnitude = (
static_cast<float>(0xFFFFU))*
msg->array[i].intensity;
288 joy_effect_.u.rumble.weak_magnitude = (
static_cast<float>(0xFFFFU))*
msg->array[i].intensity;
300 int main(
int argc,
char **argv)
309 nh_param.
param<std::string>(
"dev",
joy_dev_,
"/dev/input/js0");
322 if (joy_dev_path.empty())
324 ROS_ERROR(
"Couldn't find a joystick with name %s. Falling back to default device.",
joy_dev_name_.c_str());
328 ROS_INFO(
"Using %s as joystick device.", joy_dev_path.c_str());
335 ROS_WARN(
"joy_node: autorepeat_rate (%f Hz) > 1/coalesce_interval (%f Hz) "
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.");
349 ROS_WARN(
"joy_node: deadzone (%f) greater than 0.9, setting it to 0.9",
deadzone_);
373 double scale = -1. / (1. -
deadzone_) / 32767.;
374 double unscaled_deadzone = 32767. *
deadzone_;
389 bool first_fault =
true;
397 joy_fd = open(
joy_dev_.c_str(), O_RDONLY);
407 joy_fd = open(
joy_dev_.c_str(), O_RDONLY);
415 ROS_ERROR(
"Couldn't open joystick %s. Will retry every second.",
joy_dev_.c_str());
430 ff_fd_ = open(dev_ff.c_str(), O_RDWR);
434 struct input_event ie;
438 ie.value = 0xFFFFUL * gain / 100;
440 if (write(
ff_fd_, &ie,
sizeof(ie)) == -1)
442 ROS_WARN(
"Couldn't set gain on joystick force feedback: %s", strerror(errno));
458 char current_joy_name[128];
459 if (ioctl(joy_fd, JSIOCGNAME(
sizeof(current_joy_name)), current_joy_name) < 0)
461 strncpy(current_joy_name,
"Unknown",
sizeof(current_joy_name));
469 bool publication_pending =
false;
472 sensor_msgs::Joy joy_msg;
478 bool publish_now =
false;
479 bool publish_soon =
false;
481 FD_SET(joy_fd, &
set);
483 int select_out = select(joy_fd+1, &
set,
nullptr,
nullptr, &tv);
484 if (select_out == -1)
494 struct input_event
start;
511 if (FD_ISSET(joy_fd, &
set))
513 if (read(joy_fd, &event,
sizeof(js_event)) == -1 && errno != EAGAIN)
522 case JS_EVENT_BUTTON:
523 case JS_EVENT_BUTTON | JS_EVENT_INIT:
524 if (event.number >= joy_msg.buttons.size())
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++)
530 joy_msg.buttons[i] = 0.0;
535 if (event.value == 1)
537 joy_msg.buttons[
event.number] = 1 - joy_msg.buttons[
event.number];
542 joy_msg.buttons[
event.number] = (
event.value ? 1 : 0);
546 if (!(event.type & JS_EVENT_INIT))
556 case JS_EVENT_AXIS | JS_EVENT_INIT:
558 if (event.number >= joy_msg.axes.size())
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++)
564 joy_msg.axes[i] = 0.0;
570 if (val > unscaled_deadzone)
572 val -= unscaled_deadzone;
574 else if (val < -unscaled_deadzone)
576 val += unscaled_deadzone;
582 joy_msg.axes[
event.number] = val * scale;
589 if (!(event.type & JS_EVENT_INIT))
592 if (val > unscaled_deadzone)
594 val -= unscaled_deadzone;
596 else if (val < -unscaled_deadzone)
598 val += unscaled_deadzone;
604 joy_msg.axes[
event.number] = val * scale;
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);
628 joy_msg.header.frame_id =
joy_dev_.c_str();
633 publication_pending =
false;
634 publish_soon =
false;
640 if (!publication_pending && publish_soon)
644 publication_pending =
true;
651 tv.tv_sec = trunc(autorepeat_interval);
652 tv.tv_usec = (autorepeat_interval - tv.tv_sec) * 1e6;
670 ROS_ERROR(
"Connection to joystick device lost unexpectedly. Will reopen.");
681 int main(
int argc,
char **argv)
685 return j.
main(argc, argv);