Go to the documentation of this file.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
00033
00034 #include <stdio.h>
00035 #include <vector>
00036 #include "ros/node_handle.h"
00037 #include "ros/param.h"
00038 #include "spnav.h"
00039 #include "geometry_msgs/Vector3.h"
00040 #include "geometry_msgs/Twist.h"
00041 #include "sensor_msgs/Joy.h"
00042
00050 bool ensureThreeComponents(std::vector<double>& param)
00051 {
00052 if (param.size() == 0)
00053 {
00054 param.push_back(1);
00055 param.push_back(1);
00056 param.push_back(1);
00057 return True;
00058 }
00059 if (param.size() == 3)
00060 {
00061 return True;
00062 }
00063 if (param.size() == 1)
00064 {
00065 param.push_back(param[0]);
00066 param.push_back(param[0]);
00067 return True;
00068 }
00069 return False;
00070 }
00071
00072 int main(int argc, char **argv)
00073 {
00074 ros::init(argc, argv, "spacenav");
00075
00076 ros::NodeHandle node_handle;
00077 ros::Publisher offset_pub = node_handle.advertise<geometry_msgs::Vector3>("spacenav/offset", 2);
00078 ros::Publisher rot_offset_pub = node_handle.advertise<geometry_msgs::Vector3>("spacenav/rot_offset", 2);
00079 ros::Publisher twist_pub = node_handle.advertise<geometry_msgs::Twist>("spacenav/twist", 2);
00080 ros::Publisher joy_pub = node_handle.advertise<sensor_msgs::Joy>("spacenav/joy", 2);
00081
00082
00083 ros::NodeHandle private_nh("~");
00084 double full_scale;
00085 private_nh.param<double>("full_scale", full_scale, 512);
00086 if (full_scale < 1e-10)
00087 {
00088 full_scale = 512;
00089 }
00090
00091
00092 std::vector<double> linear_scale;
00093 std::vector<double> angular_scale;
00094 private_nh.param<std::vector<double> >("linear_scale", linear_scale, std::vector<double>(3, 1));
00095 private_nh.param<std::vector<double> >("angular_scale", angular_scale, std::vector<double>(3, 1));
00096
00097 if (!ensureThreeComponents(linear_scale))
00098 {
00099 ROS_ERROR_STREAM("Parameter " << private_nh.getNamespace() << "/linear_scale must have either one or three components.");
00100 exit(EXIT_FAILURE);
00101 }
00102 if (!ensureThreeComponents(angular_scale))
00103 {
00104 ROS_ERROR_STREAM("Parameter " << private_nh.getNamespace() << "/angular_scale must have either one or three components.");
00105 exit(EXIT_FAILURE);
00106 }
00107 ROS_DEBUG("linear_scale: %.3f %.3f %.3f", linear_scale[0], linear_scale[1], linear_scale[2]);
00108 ROS_DEBUG("angular_scale: %.3f %.3f %.3f", angular_scale[0], angular_scale[1], angular_scale[2]);
00109
00110 if (spnav_open() == -1)
00111 {
00112 ROS_ERROR("Could not open the space navigator device. Did you remember to run spacenavd (as root)?");
00113
00114 return 1;
00115 }
00116
00117
00118
00119 int static_count_threshold = 30;
00120 ros::param::get("~/static_count_threshold",static_count_threshold);
00121
00122
00123 bool zero_when_static = true;
00124 ros::param::get("~/zero_when_static",zero_when_static);
00125
00126
00127
00128
00129 double static_trans_deadband = 0.1;
00130 double static_rot_deadband = 0.1;
00131 ros::param::get("~/static_trans_deadband", static_trans_deadband);
00132 ros::param::get("~/static_rot_deadband", static_rot_deadband);
00133
00134 sensor_msgs::Joy joystick_msg;
00135 joystick_msg.axes.resize(6);
00136 joystick_msg.buttons.resize(2);
00137
00138 spnav_event sev;
00139 int no_motion_count = 0;
00140 bool motion_stale = false;
00141 double normed_vx = 0;
00142 double normed_vy = 0;
00143 double normed_vz = 0;
00144 double normed_wx = 0;
00145 double normed_wy = 0;
00146 double normed_wz = 0;
00147 while (node_handle.ok())
00148 {
00149 bool joy_stale = false;
00150 bool queue_empty = false;
00151
00152
00153
00154
00155
00156 joystick_msg.header.stamp = ros::Time().now();
00157 switch (spnav_poll_event(&sev))
00158 {
00159 case 0:
00160 queue_empty = true;
00161 if (++no_motion_count > static_count_threshold)
00162 {
00163 if ( zero_when_static ||
00164 ( fabs(normed_vx) < static_trans_deadband &&
00165 fabs(normed_vy) < static_trans_deadband &&
00166 fabs(normed_vz) < static_trans_deadband)
00167 )
00168 {
00169 normed_vx = normed_vy = normed_vz = 0;
00170 }
00171
00172 if ( zero_when_static ||
00173 ( fabs(normed_wx) < static_rot_deadband &&
00174 fabs(normed_wy) < static_rot_deadband &&
00175 fabs(normed_wz) < static_rot_deadband )
00176 )
00177 {
00178 normed_wx = normed_wy = normed_wz = 0;
00179 }
00180
00181 no_motion_count = 0;
00182 motion_stale = true;
00183 }
00184 break;
00185
00186 case SPNAV_EVENT_MOTION:
00187 normed_vx = sev.motion.z / full_scale;
00188 normed_vy = -sev.motion.x / full_scale;
00189 normed_vz = sev.motion.y / full_scale;
00190
00191 normed_wx = sev.motion.rz / full_scale;
00192 normed_wy = -sev.motion.rx / full_scale;
00193 normed_wz = sev.motion.ry / full_scale;
00194
00195 motion_stale = true;
00196 break;
00197
00198 case SPNAV_EVENT_BUTTON:
00199
00200 joystick_msg.buttons[sev.button.bnum] = sev.button.press;
00201
00202 joy_stale = true;
00203 break;
00204
00205 default:
00206 ROS_WARN("Unknown message type in spacenav. This should never happen.");
00207 break;
00208 }
00209
00210 if (motion_stale && (queue_empty || joy_stale))
00211 {
00212
00213 geometry_msgs::Vector3 offset_msg;
00214 offset_msg.x = normed_vx * linear_scale[0];
00215 offset_msg.y = normed_vy * linear_scale[1];
00216 offset_msg.z = normed_vz * linear_scale[2];
00217 offset_pub.publish(offset_msg);
00218 geometry_msgs::Vector3 rot_offset_msg;
00219 rot_offset_msg.x = normed_wx * angular_scale[0];
00220 rot_offset_msg.y = normed_wy * angular_scale[1];
00221 rot_offset_msg.z = normed_wz * angular_scale[2];
00222 rot_offset_pub.publish(rot_offset_msg);
00223
00224 geometry_msgs::Twist twist_msg;
00225 twist_msg.linear = offset_msg;
00226 twist_msg.angular = rot_offset_msg;
00227 twist_pub.publish(twist_msg);
00228
00229
00230 joystick_msg.axes[0] = normed_vx;
00231 joystick_msg.axes[1] = normed_vy;
00232 joystick_msg.axes[2] = normed_vz;
00233 joystick_msg.axes[3] = normed_wx;
00234 joystick_msg.axes[4] = normed_wy;
00235 joystick_msg.axes[5] = normed_wz;
00236
00237 no_motion_count = 0;
00238 motion_stale = false;
00239 joy_stale = true;
00240 }
00241
00242 if (joy_stale)
00243 {
00244 joy_pub.publish(joystick_msg);
00245 }
00246
00247 if (queue_empty) {
00248 usleep(1000);
00249 }
00250 }
00251
00252 spnav_close();
00253
00254 return 0;
00255 }