00001 00027 #ifndef _3D_MOUSE_H_ 00028 #define _3D_MOUSE_H_ 00029 00030 #include <ros/ros.h> 00031 00032 #include <X11/Xlib.h> 00033 #include <spnav.h> 00034 #include <boost/thread.hpp> 00035 00036 #include "threeD_mouse/geometry.h" 00037 00038 00039 namespace threedmouse 00040 { 00044 enum MouseMode 00045 { 00046 ROTATE, 00047 TRANSLATE, 00048 BOTH 00049 }; 00050 00051 class ThreeDMouse 00052 { 00053 public: 00054 ThreeDMouse(); 00055 ~ThreeDMouse(); 00056 00057 void publish(); 00058 private: 00060 ros::NodeHandle node, n_tilde; 00062 ros::Rate publish_rate; 00064 ros::Publisher pub; 00065 00066 void update_mouse_data(); 00067 00068 boost::thread thread_update_mouse_data; 00069 boost::thread thread_publish; 00070 00071 //for the 3d mouse 00072 spnav_event sev; 00073 Display *dpy; 00074 Window win; 00075 unsigned long bpix; 00076 00077 //keep the last pose read from the 3d mouse 00078 geometry::Pose last_pose; 00079 00080 MouseMode mouse_mode; 00081 00082 void info_mouse_mode(); 00083 void check_stopped(); 00084 }; 00085 } 00086 00087 00088 #endif