35 #include <linux/joystick.h> 41 #include <sensor_msgs/Joy.h> 72 stat.
summary(2,
"Joystick not open.");
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);
83 stat.
add(
"default trig val", default_trig_val_);
84 stat.
add(
"sticky buttons", sticky_buttons_);
95 const char path[] =
"/dev/input";
99 DIR *dev_dir = opendir(path);
102 ROS_ERROR(
"Couldn't open %s. Error %i: %s.", path, errno, strerror(errno));
106 while ((entry = readdir(dev_dir)) != NULL)
109 if (strncmp(entry->d_name,
"js", 2) != 0)
111 std::string current_path = std::string(path) +
"/" + entry->d_name;
112 if (stat(current_path.c_str(), &stat_buf) == -1)
114 if (!S_ISCHR(stat_buf.st_mode))
118 int joy_fd = open(current_path.c_str(), O_RDONLY);
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));
128 ROS_INFO(
"Found joystick: %s (%s).", current_joy_name, current_path.c_str());
130 if (strcmp(current_joy_name, joy_name.c_str()) == 0)
146 int main(
int argc,
char **argv)
153 pub_ = nh_.
advertise<sensor_msgs::Joy>(
"joy", 1);
154 nh_param.
param<std::string>(
"dev",
joy_dev_,
"/dev/input/js0");
163 if (!joy_dev_name_.empty())
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());
170 ROS_INFO(
"Using %s as joystick device.", joy_dev_path.c_str());
171 joy_dev_ = joy_dev_path;
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_);
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.");
186 ROS_WARN(
"joy_node: deadzone (%f) greater than 0.9, setting it to 0.9", deadzone_);
192 ROS_WARN(
"joy_node: deadzone_ (%f) less than 0, setting to 0.", deadzone_);
196 if (autorepeat_rate_ < 0)
198 ROS_WARN(
"joy_node: autorepeat_rate (%f) less than 0, setting to 0.", autorepeat_rate_);
199 autorepeat_rate_ = 0;
202 if (coalesce_interval_ < 0)
204 ROS_WARN(
"joy_node: coalesce_interval (%f) less than 0, setting to 0.", coalesce_interval_);
205 coalesce_interval_ = 0;
210 double scale = -1. / (1. -
deadzone_) / 32767.;
211 double unscaled_deadzone = 32767. *
deadzone_;
226 bool first_fault =
true;
232 joy_fd = open(joy_dev_.c_str(), O_RDONLY);
242 joy_fd = open(joy_dev_.c_str(), O_RDONLY);
248 ROS_ERROR(
"Couldn't open joystick %s. Will retry every second.", joy_dev_.c_str());
260 bool publication_pending =
false;
263 sensor_msgs::Joy joy_msg;
265 sensor_msgs::Joy last_published_joy_msg;
266 sensor_msgs::Joy sticky_buttons_joy_msg;
271 bool publish_now =
false;
272 bool publish_soon =
false;
274 FD_SET(joy_fd, &
set);
277 int select_out = select(joy_fd+1, &
set, NULL, NULL, &tv);
279 if (select_out == -1)
288 if (FD_ISSET(joy_fd, &
set))
290 if (read(joy_fd, &event,
sizeof(js_event)) == -1 && errno != EAGAIN)
298 case JS_EVENT_BUTTON:
299 case JS_EVENT_BUTTON | JS_EVENT_INIT:
300 if(event.number >= joy_msg.buttons.size())
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;
312 joy_msg.buttons[
event.number] = (
event.value ? 1 : 0);
315 if (!(event.type & JS_EVENT_INIT))
321 case JS_EVENT_AXIS | JS_EVENT_INIT:
323 if(event.number >= joy_msg.axes.size())
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;
335 if(default_trig_val_){
337 if (val > unscaled_deadzone)
338 val -= unscaled_deadzone;
339 else if (val < -unscaled_deadzone)
340 val += unscaled_deadzone;
343 joy_msg.axes[
event.number] = val * scale;
350 if (!(event.type & JS_EVENT_INIT))
353 if(val > unscaled_deadzone)
354 val -= unscaled_deadzone;
355 else if(val < -unscaled_deadzone)
356 val += unscaled_deadzone;
359 joy_msg.axes[
event.number]= val * scale;
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);
378 if (sticky_buttons_ ==
true) {
380 for (
size_t i = 0; i < joy_msg.buttons.size(); i++) {
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;
390 last_published_joy_msg = joy_msg;
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];
398 pub_.
publish(sticky_buttons_joy_msg);
405 publication_pending =
false;
406 publish_soon =
false;
412 if (!publication_pending && publish_soon)
414 tv.tv_sec = trunc(coalesce_interval_);
415 tv.tv_usec = (coalesce_interval_ - tv.tv_sec) * 1e6;
416 publication_pending =
true;
422 if (!tv_set && autorepeat_rate_ > 0)
424 tv.tv_sec = trunc(autorepeat_interval);
425 tv.tv_usec = (autorepeat_interval - tv.tv_sec) * 1e6;
442 ROS_ERROR(
"Connection to joystick device lost unexpectedly. Will reopen.");
452 int main(
int argc,
char **argv)
456 return j.
main(argc, argv);
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)
void add(const std::string &name, TaskFunction f)
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...
int main(int argc, char **argv)
Opens joystick port, reads from port and publishes while node is active.
double coalesce_interval_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Opens, reads from and publishes joystick events.
uint32_t getNumSubscribers() const
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Publishes diagnostics and status.
std::string getTopic() const
void add(const std::string &key, const T &val)
std::string joy_dev_name_
ROSCPP_DECL void spinOnce()
diagnostic_updater::Updater diagnostic_