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 "ros/node_handle.h"
00036 #include "ros/param.h"
00037 #include "spnav.h"
00038 #include "geometry_msgs/Vector3.h"
00039 #include "geometry_msgs/Twist.h"
00040 #include "sensor_msgs/Joy.h"
00041
00042 #define FULL_SCALE (512.0)
00043
00044
00045 int main(int argc, char **argv)
00046 {
00047 ros::init(argc, argv, "spacenav");
00048
00049 ros::NodeHandle node_handle;
00050 ros::Publisher offset_pub = node_handle.advertise<geometry_msgs::Vector3>("spacenav/offset", 2);
00051 ros::Publisher rot_offset_pub = node_handle.advertise<geometry_msgs::Vector3>("spacenav/rot_offset", 2);
00052 ros::Publisher twist_pub = node_handle.advertise<geometry_msgs::Twist>("spacenav/twist", 2);
00053 ros::Publisher joy_pub = node_handle.advertise<sensor_msgs::Joy>("spacenav/joy", 2);
00054
00055 if (spnav_open() == -1)
00056 {
00057 ROS_ERROR("Could not open the space navigator device. Did you remember to run spacenavd (as root)?");
00058
00059 return 1;
00060 }
00061
00062
00063
00064 int static_count_threshold = 30;
00065 ros::param::get("~/static_count_threshold",static_count_threshold);
00066
00067
00068 bool zero_when_static = true;
00069 ros::param::get("~/zero_when_static",zero_when_static);
00070
00071
00072
00073
00074 double static_trans_deadband = 50,
00075 static_rot_deadband = 50;
00076 ros::param::get("~/static_trans_deadband",static_trans_deadband);
00077 ros::param::get("~/static_rot_deadband",static_rot_deadband);
00078
00079 sensor_msgs::Joy joystick_msg;
00080 joystick_msg.axes.resize(6);
00081 joystick_msg.buttons.resize(2);
00082
00083 spnav_event sev;
00084 int no_motion_count = 0;
00085 bool motion_stale = false;
00086 geometry_msgs::Vector3 offset_msg;
00087 geometry_msgs::Vector3 rot_offset_msg;
00088 geometry_msgs::Twist twist_msg;
00089 while (node_handle.ok())
00090 {
00091 bool joy_stale = false;
00092 bool queue_empty = false;
00093
00094
00095
00096
00097
00098 joystick_msg.header.stamp = ros::Time().now();
00099 switch (spnav_poll_event(&sev))
00100 {
00101 case 0:
00102 queue_empty = true;
00103 if (++no_motion_count > static_count_threshold)
00104 {
00105 if ( zero_when_static ||
00106 ( fabs(offset_msg.x) < static_trans_deadband &&
00107 fabs(offset_msg.y) < static_trans_deadband &&
00108 fabs(offset_msg.z) < static_trans_deadband)
00109 )
00110 {
00111 offset_msg.x = offset_msg.y = offset_msg.z = 0;
00112 }
00113
00114 if ( zero_when_static ||
00115 ( fabs(rot_offset_msg.x) < static_rot_deadband &&
00116 fabs(rot_offset_msg.y) < static_rot_deadband &&
00117 fabs(rot_offset_msg.z) < static_rot_deadband )
00118 )
00119 {
00120 rot_offset_msg.x = rot_offset_msg.y = rot_offset_msg.z = 0;
00121 }
00122
00123 no_motion_count = 0;
00124 motion_stale = true;
00125 }
00126 break;
00127
00128 case SPNAV_EVENT_MOTION:
00129 offset_msg.x = sev.motion.z;
00130 offset_msg.y = -sev.motion.x;
00131 offset_msg.z = sev.motion.y;
00132
00133 rot_offset_msg.x = sev.motion.rz;
00134 rot_offset_msg.y = -sev.motion.rx;
00135 rot_offset_msg.z = sev.motion.ry;
00136
00137 motion_stale = true;
00138 break;
00139
00140 case SPNAV_EVENT_BUTTON:
00141
00142 joystick_msg.buttons[sev.button.bnum] = sev.button.press;
00143
00144 joy_stale = true;
00145 break;
00146
00147 default:
00148 ROS_WARN("Unknown message type in spacenav. This should never happen.");
00149 break;
00150 }
00151
00152 if (motion_stale && (queue_empty || joy_stale))
00153 {
00154 offset_pub.publish(offset_msg);
00155 rot_offset_pub.publish(rot_offset_msg);
00156
00157 twist_msg.linear = offset_msg;
00158 twist_msg.angular = rot_offset_msg;
00159 twist_pub.publish(twist_msg);
00160
00161 joystick_msg.axes[0] = offset_msg.x / FULL_SCALE;
00162 joystick_msg.axes[1] = offset_msg.y / FULL_SCALE;
00163 joystick_msg.axes[2] = offset_msg.z / FULL_SCALE;
00164 joystick_msg.axes[3] = rot_offset_msg.x / FULL_SCALE;
00165 joystick_msg.axes[4] = rot_offset_msg.y / FULL_SCALE;
00166 joystick_msg.axes[5] = rot_offset_msg.z / FULL_SCALE;
00167
00168 no_motion_count = 0;
00169 motion_stale = false;
00170 joy_stale = true;
00171 }
00172
00173 if (joy_stale)
00174 {
00175 joy_pub.publish(joystick_msg);
00176 }
00177
00178 if (queue_empty) {
00179 usleep(1000);
00180 }
00181 }
00182
00183 spnav_close();
00184
00185 return 0;
00186 }