$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 /* 00031 * Author: Stuart Glaser 00032 */ 00033 00034 #include <stdio.h> 00035 #include "ros/node_handle.h" 00036 #include "spnav.h" 00037 #include "geometry_msgs/Vector3.h" 00038 #include "geometry_msgs/Twist.h" 00039 #include "sensor_msgs/Joy.h" 00040 00041 #define FULL_SCALE (512.0) 00042 //Used to scale joystick output to be in [-1, 1]. Estimated from data, and not necessarily correct. 00043 00044 int main(int argc, char **argv) 00045 { 00046 ros::init(argc, argv, "spacenav"); 00047 00048 ros::NodeHandle node_handle; 00049 ros::Publisher offset_pub = node_handle.advertise<geometry_msgs::Vector3>("spacenav/offset", 2); 00050 ros::Publisher rot_offset_pub = node_handle.advertise<geometry_msgs::Vector3>("spacenav/rot_offset", 2); 00051 ros::Publisher twist_pub = node_handle.advertise<geometry_msgs::Twist>("spacenav/twist", 2); 00052 ros::Publisher joy_pub = node_handle.advertise<sensor_msgs::Joy>("spacenav/joy", 2); 00053 00054 if (spnav_open() == -1) 00055 { 00056 ROS_ERROR("Could not open the space navigator device. Did you remember to run spacenavd (as root)?"); 00057 00058 return 1; 00059 } 00060 00061 sensor_msgs::Joy joystick_msg; 00062 joystick_msg.axes.resize(6); 00063 joystick_msg.buttons.resize(2); 00064 00065 spnav_event sev; 00066 int no_motion_count = 0; 00067 bool motion_stale = false; 00068 geometry_msgs::Vector3 offset_msg; 00069 geometry_msgs::Vector3 rot_offset_msg; 00070 geometry_msgs::Twist twist_msg; 00071 while (node_handle.ok()) 00072 { 00073 bool joy_stale = false; 00074 bool queue_empty = false; 00075 00076 // Sleep when the queue is empty. 00077 // If the queue is empty 30 times in a row output zeros. 00078 // Output changes each time a button event happens, or when a motion 00079 // event happens and the queue is empty. 00080 joystick_msg.header.stamp = ros::Time().now(); 00081 switch (spnav_poll_event(&sev)) 00082 { 00083 case 0: 00084 queue_empty = true; 00085 if (++no_motion_count > 30) 00086 { 00087 offset_msg.x = offset_msg.y = offset_msg.z = 0; 00088 rot_offset_msg.x = rot_offset_msg.y = rot_offset_msg.z = 0; 00089 00090 no_motion_count = 0; 00091 motion_stale = true; 00092 } 00093 break; 00094 00095 case SPNAV_EVENT_MOTION: 00096 offset_msg.x = sev.motion.z; 00097 offset_msg.y = -sev.motion.x; 00098 offset_msg.z = sev.motion.y; 00099 00100 rot_offset_msg.x = sev.motion.rz; 00101 rot_offset_msg.y = -sev.motion.rx; 00102 rot_offset_msg.z = sev.motion.ry; 00103 00104 //printf("%lf %lf %lf\n", rot_offset_msg.x, rot_offset_msg.y, rot_offset_msg.z); 00105 00106 motion_stale = true; 00107 break; 00108 00109 case SPNAV_EVENT_BUTTON: 00110 //printf("type, press, bnum = <%d, %d, %d>\n", sev.button.type, sev.button.press, sev.button.bnum); 00111 joystick_msg.buttons[sev.button.bnum] = sev.button.press; 00112 00113 joy_stale = true; 00114 break; 00115 00116 default: 00117 ROS_WARN("Unknown message type in spacenav. This should never happen."); 00118 break; 00119 } 00120 00121 if (motion_stale && (queue_empty || joy_stale)) 00122 { 00123 offset_pub.publish(offset_msg); 00124 rot_offset_pub.publish(rot_offset_msg); 00125 00126 twist_msg.linear = offset_msg; 00127 twist_msg.angular = rot_offset_msg; 00128 twist_pub.publish(twist_msg); 00129 00130 joystick_msg.axes[0] = offset_msg.x / FULL_SCALE; 00131 joystick_msg.axes[1] = offset_msg.y / FULL_SCALE; 00132 joystick_msg.axes[2] = offset_msg.z / FULL_SCALE; 00133 joystick_msg.axes[3] = rot_offset_msg.x / FULL_SCALE; 00134 joystick_msg.axes[4] = rot_offset_msg.y / FULL_SCALE; 00135 joystick_msg.axes[5] = rot_offset_msg.z / FULL_SCALE; 00136 00137 no_motion_count = 0; 00138 motion_stale = false; 00139 joy_stale = true; 00140 } 00141 00142 if (joy_stale) 00143 { 00144 joy_pub.publish(joystick_msg); 00145 } 00146 00147 if (queue_empty) 00148 usleep(1000); 00149 } 00150 00151 return 0; 00152 }