00001 00031 #ifndef CYBERGLOVE_PUBLISHER_H_ 00032 # define CYBERGLOVE_PUBLISHER_H_ 00033 00034 #include <ros/ros.h> 00035 #include <vector> 00036 #include <boost/smart_ptr.hpp> 00037 00038 #include "cyberglove/serial_glove.hpp" 00039 00040 //messages 00041 #include <sensor_msgs/JointState.h> 00042 #include "cyberglove/xml_calibration_parser.h" 00043 00044 using namespace ros; 00045 00046 namespace cyberglove{ 00047 00048 class CyberglovePublisher 00049 { 00050 public: 00052 CyberglovePublisher(); 00053 00055 ~CyberglovePublisher(); 00056 00057 Publisher cyberglove_pub; 00058 void initialize_calibration(std::string path_to_calibration); 00059 bool isPublishing(); 00060 void setPublishing(bool value); 00061 private: 00063 // CALLBACKS // 00065 00066 //ros node handle 00067 NodeHandle node, n_tilde; 00068 Rate sampling_rate; 00069 unsigned int publish_counter_max, publish_counter_index; 00070 00072 boost::shared_ptr<CybergloveSerial> serial_glove; 00073 00082 void glove_callback(std::vector<float> glove_pos, bool light_on); 00083 00084 std::string path_to_glove; 00085 bool publishing; 00086 00088 xml_calibration_parser::XmlCalibrationParser calibration_parser; 00089 00090 Publisher cyberglove_raw_pub; 00091 00092 sensor_msgs::JointState jointstate_msg; 00093 sensor_msgs::JointState jointstate_raw_msg; 00094 00095 void add_jointstate(float position, std::string joint_name); 00096 00097 std::vector<float> calibration_values; 00098 00099 std::vector<std::vector<float> > glove_positions; 00100 }; // end class CyberglovePublisher 00101 00102 } // end namespace 00103 #endif /* !CYBERGLOVE_PUBLISHER_H_ */ 00104 00105 /* For the emacs weenies in the crowd. 00106 Local Variables: 00107 c-basic-offset: 2 00108 End: 00109 */