00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00040 #include <unistd.h>
00041 #include <math.h>
00042 #include <linux/joystick.h>
00043 #include <fcntl.h>
00044 #include <diagnostic_updater/diagnostic_updater.h>
00045 #include "ros/ros.h"
00046 #include <sensor_msgs/Joy.h>
00047
00049 class Joystick
00050 {
00051 private:
00052 ros::NodeHandle nh_;
00053 bool open_;
00054 std::string joy_dev_;
00055 double deadzone_;
00056 double autorepeat_rate_;
00057 double coalesce_interval_;
00058 double max_period_with_no_events_;
00059 int event_count_;
00060 int pub_count_;
00061 ros::Publisher pub_;
00062 double lastDiagTime_;
00063
00064 diagnostic_updater::Updater diagnostic_;
00065
00067 void diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
00068 {
00069 double now = ros::Time::now().toSec();
00070 double interval = now - lastDiagTime_;
00071 if (open_)
00072 stat.summary(0, "OK");
00073 else
00074 stat.summary(2, "Joystick not open.");
00075
00076 stat.add("topic", pub_.getTopic());
00077 stat.add("device", joy_dev_);
00078 stat.add("dead zone", deadzone_);
00079 stat.add("autorepeat rate (Hz)", autorepeat_rate_);
00080 stat.add("coalesce interval (s)", coalesce_interval_);
00081 stat.add("recent joystick event rate (Hz)", event_count_ / interval);
00082 stat.add("recent publication rate (Hz)", pub_count_ / interval);
00083 stat.add("subscribers", pub_.getNumSubscribers());
00084 event_count_ = 0;
00085 pub_count_ = 0;
00086 lastDiagTime_ = now;
00087 }
00088
00089 public:
00090 Joystick() : nh_(), diagnostic_()
00091 {}
00092
00094 int main(int argc, char **argv)
00095 {
00096 diagnostic_.add("Joystick Driver Status", this, &Joystick::diagnostics);
00097 diagnostic_.setHardwareID("none");
00098
00099
00100 ros::NodeHandle nh_param("~");
00101 pub_ = nh_.advertise<sensor_msgs::Joy>("joy", 1);
00102 nh_param.param<std::string>("dev", joy_dev_, "/dev/input/js0");
00103 nh_param.param<double>("deadzone", deadzone_, 0.05);
00104 nh_param.param<double>("autorepeat_rate", autorepeat_rate_, 0);
00105 nh_param.param<double>("coalesce_interval", coalesce_interval_, 0.001);
00106 nh_param.param<double>("max_period_with_no_events", max_period_with_no_events_, 0.5);
00107
00108
00109 if (autorepeat_rate_ > 1 / coalesce_interval_)
00110 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_);
00111
00112 if (deadzone_ >= 1)
00113 {
00114 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.");
00115 deadzone_ /= 32767;
00116 }
00117
00118 if (deadzone_ > 0.9)
00119 {
00120 ROS_WARN("joy_node: deadzone (%f) greater than 0.9, setting it to 0.9", deadzone_);
00121 deadzone_ = 0.9;
00122 }
00123
00124 if (deadzone_ < 0)
00125 {
00126 ROS_WARN("joy_node: deadzone_ (%f) less than 0, setting to 0.", deadzone_);
00127 deadzone_ = 0;
00128 }
00129
00130 if (autorepeat_rate_ < 0)
00131 {
00132 ROS_WARN("joy_node: autorepeat_rate (%f) less than 0, setting to 0.", autorepeat_rate_);
00133 autorepeat_rate_ = 0;
00134 }
00135
00136 if (coalesce_interval_ < 0)
00137 {
00138 ROS_WARN("joy_node: coalesce_interval (%f) less than 0, setting to 0.", coalesce_interval_);
00139 coalesce_interval_ = 0;
00140 }
00141
00142 if ((max_period_with_no_events_ < 0) || (max_period_with_no_events_ > 1.0))
00143 {
00144 ROS_WARN("joy_node: max_period_with_no_events (%f) shoul be with [0.0, 1.0], setting to 0.", max_period_with_no_events_);
00145 max_period_with_no_events_ = 0.0;
00146 }
00147
00148
00149 double autorepeat_interval = 1 / autorepeat_rate_;
00150 double scale = -1. / (1. - deadzone_) / 32767.;
00151 double unscaled_deadzone = 32767. * deadzone_;
00152
00153 js_event event;
00154 struct timeval tv;
00155 fd_set set;
00156 int joy_fd;
00157 event_count_ = 0;
00158 pub_count_ = 0;
00159 lastDiagTime_ = ros::Time::now().toSec();
00160
00161 const ros::Duration max_duration_with_no_events(max_period_with_no_events_);
00162 ros::Time last_event_time(0.0);
00163
00164
00165 while (nh_.ok())
00166 {
00167 open_ = false;
00168 diagnostic_.force_update();
00169 bool first_fault = true;
00170 while (true)
00171 {
00172 ros::spinOnce();
00173 if (!nh_.ok())
00174 goto cleanup;
00175 joy_fd = open(joy_dev_.c_str(), O_RDONLY);
00176 if (joy_fd != -1)
00177 {
00178
00179
00180
00181
00182
00183
00184 close(joy_fd);
00185 joy_fd = open(joy_dev_.c_str(), O_RDONLY);
00186 }
00187 if (joy_fd != -1)
00188 break;
00189 if (first_fault)
00190 {
00191 ROS_ERROR("Couldn't open joystick %s. Will retry every second.", joy_dev_.c_str());
00192 first_fault = false;
00193 }
00194 sleep(1.0);
00195 diagnostic_.update();
00196 }
00197
00198 ROS_INFO("Opened joystick: %s. deadzone_: %f.", joy_dev_.c_str(), deadzone_);
00199 open_ = true;
00200 diagnostic_.force_update();
00201
00202 bool tv_set = false;
00203 bool publication_pending = false;
00204 tv.tv_sec = 1;
00205 tv.tv_usec = 0;
00206 sensor_msgs::Joy joy_msg;
00207 while (nh_.ok())
00208 {
00209 ros::spinOnce();
00210
00211 bool publish_now = false;
00212 bool publish_soon = false;
00213 FD_ZERO(&set);
00214 FD_SET(joy_fd, &set);
00215
00216
00217 int select_out = select(joy_fd+1, &set, NULL, NULL, &tv);
00218
00219 if (select_out == -1)
00220 {
00221 tv.tv_sec = 0;
00222 tv.tv_usec = 0;
00223
00224 continue;
00225
00226 }
00227
00228 if (FD_ISSET(joy_fd, &set))
00229 {
00230 if (read(joy_fd, &event, sizeof(js_event)) == -1 && errno != EAGAIN)
00231 break;
00232
00233
00234 joy_msg.header.stamp = ros::Time().now();
00235 event_count_++;
00236 switch(event.type)
00237 {
00238 case JS_EVENT_BUTTON:
00239 case JS_EVENT_BUTTON | JS_EVENT_INIT:
00240 if(event.number >= joy_msg.buttons.size())
00241 {
00242 int old_size = joy_msg.buttons.size();
00243 joy_msg.buttons.resize(event.number+1);
00244 for(unsigned int i=old_size;i<joy_msg.buttons.size();i++)
00245 joy_msg.buttons[i] = 0.0;
00246 }
00247 joy_msg.buttons[event.number] = (event.value ? 1 : 0);
00248
00249
00250 if (!(event.type & JS_EVENT_INIT))
00251 {
00252 publish_now = true;
00253 last_event_time = ros::Time::now();
00254 }
00255 else
00256 publish_soon = true;
00257 break;
00258 case JS_EVENT_AXIS:
00259 case JS_EVENT_AXIS | JS_EVENT_INIT:
00260 if(event.number >= joy_msg.axes.size())
00261 {
00262 int old_size = joy_msg.axes.size();
00263 joy_msg.axes.resize(event.number+1);
00264 for(unsigned int i=old_size;i<joy_msg.axes.size();i++)
00265 joy_msg.axes[i] = 0.0;
00266 }
00267 if (!(event.type & JS_EVENT_INIT))
00268 {
00269 double val = event.value;
00270
00271 if (val > unscaled_deadzone)
00272 val -= unscaled_deadzone;
00273 else if (val < -unscaled_deadzone)
00274 val += unscaled_deadzone;
00275 else
00276 val = 0;
00277 joy_msg.axes[event.number] = val * scale;
00278 }
00279
00280 publish_soon = true;
00281 last_event_time = ros::Time::now();
00282 break;
00283 default:
00284 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);
00285 break;
00286 }
00287 }
00288 else if (tv_set)
00289 publish_now = true;
00290
00291 if (publish_now)
00292 {
00293
00294
00295
00296
00297
00298 publish_now = false;
00299 tv_set = false;
00300 publication_pending = false;
00301 publish_soon = false;
00302
00303 if ((ros::Time::now() - last_event_time) < max_duration_with_no_events)
00304 {
00305 pub_.publish(joy_msg);
00306 pub_count_++;
00307 }
00308 }
00309
00310
00311
00312 if (!publication_pending && publish_soon)
00313 {
00314 tv.tv_sec = trunc(coalesce_interval_);
00315 tv.tv_usec = (coalesce_interval_ - tv.tv_sec) * 1e6;
00316 publication_pending = true;
00317 tv_set = true;
00318
00319 }
00320
00321
00322 if (!tv_set && autorepeat_rate_ > 0)
00323 {
00324 tv.tv_sec = trunc(autorepeat_interval);
00325 tv.tv_usec = (autorepeat_interval - tv.tv_sec) * 1e6;
00326 tv_set = true;
00327
00328 }
00329
00330 if (!tv_set)
00331 {
00332 tv.tv_sec = 1;
00333 tv.tv_usec = 0;
00334 }
00335
00336 diagnostic_.update();
00337 }
00338
00339 close(joy_fd);
00340 ros::spinOnce();
00341 if (nh_.ok())
00342 ROS_ERROR("Connection to joystick device lost unexpectedly. Will reopen.");
00343 }
00344
00345 cleanup:
00346 ROS_INFO("joy_node shut down.");
00347
00348 return 0;
00349 }
00350 };
00351
00352 int main(int argc, char **argv)
00353 {
00354 ros::init(argc, argv, "joy_node");
00355 Joystick j;
00356 return j.main(argc, argv);
00357 }