00001 00029 #ifndef CYBERGLOVE_PUBLISHER_H_ 00030 # define CYBERGLOVE_PUBLISHER_H_ 00031 00032 #include <ros/ros.h> 00033 #include <vector> 00034 00035 //messages 00036 #include <sensor_msgs/JointState.h> 00037 #include "cyberglove/xml_calibration_parser.h" 00038 00039 using namespace ros; 00040 00041 namespace cyberglove_publisher{ 00042 00043 class CyberglovePublisher 00044 { 00045 public: 00047 CyberglovePublisher(); 00048 00050 ~CyberglovePublisher(); 00051 00052 Publisher cyberglove_pub; 00053 void initialize_calibration(std::string path_to_calibration); 00054 void publish(); 00055 bool isPublishing(); 00056 void setPublishing(bool value); 00057 private: 00059 // CALLBACKS // 00061 00062 //ros node handle 00063 NodeHandle node, n_tilde; 00064 Rate publish_rate; 00065 std::string path_to_glove; 00066 bool publishing; 00067 00069 xml_calibration_parser::XmlCalibrationParser calibration_parser; 00070 00071 Publisher cyberglove_raw_pub; 00072 00073 sensor_msgs::JointState jointstate_msg; 00074 sensor_msgs::JointState jointstate_raw_msg; 00075 00076 void add_jointstate(float position, std::string joint_name); 00077 00078 std::vector<float> calibration_values; 00079 00080 float* glovePositions; 00081 00082 bool checkGloveState(); 00083 00084 }; // end class CyberglovePublisher 00085 00086 } // end namespace 00087 #endif /* !CYBERGLOVE_PUBLISHER_H_ */