00001
00030
00031 #include <ros/ros.h>
00032
00033
00034 #include <string>
00035 #include <sstream>
00036
00037 #include "cyberglove/serial_glove.h"
00038 #include "cyberglove/cyberglove_publisher.h"
00039
00040 using namespace ros;
00041 using namespace xml_calibration_parser;
00042
00043 namespace cyberglove_publisher{
00044
00046
00048
00049 CyberglovePublisher::CyberglovePublisher()
00050 : n_tilde("~"), publish_rate(0.0), path_to_glove("/dev/ttyS0"), publishing(true)
00051 {
00052
00053 std::string path_to_calibration;
00054 n_tilde.param("path_to_calibration", path_to_calibration, std::string("/etc/robot/calibration.d/cyberglove.cal"));
00055 ROS_INFO("Calibration file loaded for the Cyberglove: %s", path_to_calibration.c_str());
00056
00057 initialize_calibration(path_to_calibration);
00058
00059
00060 double publish_freq;
00061 n_tilde.param("publish_frequency", publish_freq, 20.0);
00062 publish_rate = Rate(publish_freq);
00063
00064
00065 n_tilde.param("path_to_glove", path_to_glove, std::string("/dev/ttyS0"));
00066 ROS_INFO("Opening glove on port: %s", path_to_glove.c_str());
00067
00068 int error = setup_glove( path_to_glove.c_str() );
00069
00070 sleep(1);
00071
00072 if( error != 0 )
00073 ROS_ERROR("Couldn't initialize the glove, is the glove plugged in?");
00074 else
00075 {
00076
00077 std::string prefix;
00078 std::string searched_param;
00079 n_tilde.searchParam("cyberglove_prefix", searched_param);
00080 n_tilde.param(searched_param, prefix, std::string());
00081 std::string full_topic = prefix + "/calibrated/joint_states";
00082 cyberglove_pub = n_tilde.advertise<sensor_msgs::JointState>(full_topic, 2);
00083
00084
00085 n_tilde.searchParam("cyberglove_prefix", searched_param);
00086 n_tilde.param(searched_param, prefix, std::string());
00087 full_topic = prefix + "/raw/joint_states";
00088 cyberglove_raw_pub = n_tilde.advertise<sensor_msgs::JointState>(full_topic, 2);
00089 }
00090
00091
00092 jointstate_msg.name.push_back("G_ThumbRotate");
00093 jointstate_msg.name.push_back("G_ThumbMPJ");
00094 jointstate_msg.name.push_back("G_ThumbIJ");
00095 jointstate_msg.name.push_back("G_ThumbAb");
00096 jointstate_msg.name.push_back("G_IndexMPJ");
00097 jointstate_msg.name.push_back("G_IndexPIJ");
00098 jointstate_msg.name.push_back("G_IndexDIJ");
00099 jointstate_msg.name.push_back("G_MiddleMPJ");
00100 jointstate_msg.name.push_back("G_MiddlePIJ");
00101 jointstate_msg.name.push_back("G_MiddleDIJ");
00102 jointstate_msg.name.push_back("G_MiddleIndexAb");
00103 jointstate_msg.name.push_back("G_RingMPJ");
00104 jointstate_msg.name.push_back("G_RingPIJ");
00105 jointstate_msg.name.push_back("G_RingDIJ");
00106 jointstate_msg.name.push_back("G_RingMiddleAb");
00107 jointstate_msg.name.push_back("G_PinkieMPJ");
00108 jointstate_msg.name.push_back("G_PinkiePIJ");
00109 jointstate_msg.name.push_back("G_PinkieDIJ");
00110 jointstate_msg.name.push_back("G_PinkieRingAb");
00111 jointstate_msg.name.push_back("G_PalmArch");
00112 jointstate_msg.name.push_back("G_WristPitch");
00113 jointstate_msg.name.push_back("G_WristYaw");
00114
00115 jointstate_raw_msg.name = jointstate_msg.name;
00116 }
00117
00118 CyberglovePublisher::~CyberglovePublisher()
00119 {
00120 }
00121
00122 void CyberglovePublisher::initialize_calibration(std::string path_to_calibration)
00123 {
00124 calibration_parser = XmlCalibrationParser(path_to_calibration);
00125 }
00126
00127 bool CyberglovePublisher::isPublishing()
00128 {
00129 if (publishing)
00130 {
00131 return true;
00132 }
00133 else
00134 {
00135
00136 if( checkGloveState() )
00137 {
00138 ROS_INFO("The glove button was switched on, starting to publish data.");
00139 publishing = true;
00140 }
00141
00142 ros::spinOnce();
00143 publish_rate.sleep();
00144 return false;
00145 }
00146 }
00147
00148 void CyberglovePublisher::setPublishing(bool value){
00149 publishing = value;
00150 }
00151
00153
00155 void CyberglovePublisher::publish()
00156 {
00157
00158
00159 if( !checkGloveState() )
00160 {
00161 publishing = false;
00162 ROS_INFO("The glove button is off, no data will be read / sent");
00163 ros::spinOnce();
00164 publish_rate.sleep();
00165 return;
00166 }
00167
00168
00169 try
00170 {
00171 glovePositions = glove_get_values();
00172 }
00173 catch(int e)
00174 {
00175 ROS_ERROR("The glove values can't be read");
00176 ros::spinOnce();
00177 publish_rate.sleep();
00178 return;
00179 }
00180
00181
00182 jointstate_msg.effort.clear();
00183 jointstate_msg.position.clear();
00184 jointstate_msg.velocity.clear();
00185 jointstate_raw_msg.effort.clear();
00186 jointstate_raw_msg.position.clear();
00187 jointstate_raw_msg.velocity.clear();
00188
00189
00190 for(unsigned int i=0; i<GLOVE_SIZE; ++i)
00191 {
00192 jointstate_raw_msg.position.push_back(glovePositions[i]);
00193 add_jointstate(glovePositions[i], jointstate_msg.name[i]);
00194 }
00195
00196 cyberglove_pub.publish(jointstate_msg);
00197 cyberglove_raw_pub.publish(jointstate_raw_msg);
00198
00199 ros::spinOnce();
00200 publish_rate.sleep();
00201 }
00202
00203 void CyberglovePublisher::add_jointstate(float position, std::string joint_name)
00204 {
00205
00206 jointstate_msg.effort.push_back(0.0);
00207
00208
00209 float calibration_value = calibration_parser.get_calibration_value(position, joint_name);
00210 std::cout << calibration_value << std::endl;
00211
00212 jointstate_msg.position.push_back(calibration_value);
00213
00214
00215 jointstate_msg.velocity.push_back(0.0);
00216 }
00217
00218 bool CyberglovePublisher::checkGloveState()
00219 {
00220 int gloveButtonState = -1;
00221 gloveButtonState = read_button_value();
00222
00223
00224 switch( gloveButtonState)
00225 {
00226 case 0:
00227 return false;
00228 case 1:
00229 return true;
00230 default:
00231 ROS_ERROR("The glove button state value couldn't be read.");
00232 return false;
00233 }
00234 }
00235
00236 }
00237
00238