00001
00029
00030 #include <ros/ros.h>
00031
00032
00033 #include <string>
00034
00035
00036 #include "sr_remappers/shadowhand_to_cyberglove_remapper.h"
00037 #include <sr_robot_msgs/sendupdate.h>
00038 #include <sr_robot_msgs/joint.h>
00039 using namespace ros;
00040
00041 namespace shadowhand_to_cyberglove_remapper
00042 {
00043
00044 const int ShadowhandToCybergloveRemapper::number_hand_joints = 20;
00045
00046 ShadowhandToCybergloveRemapper::ShadowhandToCybergloveRemapper() :
00047 n_tilde("~")
00048 {
00049 joints_names.resize(number_hand_joints);
00050 ShadowhandToCybergloveRemapper::init_names();
00051
00052 std::string param;
00053 std::string path;
00054 n_tilde.searchParam("cyberglove_mapping_path", param);
00055 n_tilde.param(param, path, std::string());
00056 calibration_parser = new CalibrationParser(path);
00057 ROS_INFO("Mapping file loaded for the Cyberglove: %s", path.c_str());
00058
00059 std::string prefix;
00060 std::string searched_param;
00061 n_tilde.searchParam("cyberglove_prefix", searched_param);
00062 n_tilde.param(searched_param, prefix, std::string());
00063
00064 std::string full_topic = prefix + "/calibrated/joint_states";
00065
00066 cyberglove_jointstates_sub = node.subscribe(full_topic, 10, &ShadowhandToCybergloveRemapper::jointstatesCallback, this);
00067
00068 n_tilde.searchParam("sendupdate_prefix", searched_param);
00069 n_tilde.param(searched_param, prefix, std::string());
00070 full_topic = prefix + "sendupdate";
00071
00072 shadowhand_pub = node.advertise<sr_robot_msgs::sendupdate> (full_topic, 5);
00073 }
00074
00075 void ShadowhandToCybergloveRemapper::init_names()
00076 {
00077 joints_names[0] = "THJ1";
00078 joints_names[1] = "THJ2";
00079 joints_names[2] = "THJ3";
00080 joints_names[3] = "THJ4";
00081 joints_names[4] = "THJ5";
00082 joints_names[5] = "FFJ0";
00083 joints_names[6] = "FFJ3";
00084 joints_names[7] = "FFJ4";
00085 joints_names[8] = "MFJ0";
00086 joints_names[9] = "MFJ3";
00087 joints_names[10] = "MFJ4";
00088 joints_names[11] = "RFJ0";
00089 joints_names[12] = "RFJ3";
00090 joints_names[13] = "RFJ4";
00091 joints_names[14] = "LFJ0";
00092 joints_names[15] = "LFJ3";
00093 joints_names[16] = "LFJ4";
00094 joints_names[17] = "LFJ5";
00095 joints_names[18] = "WRJ1";
00096 joints_names[19] = "WRJ2";
00097 }
00098
00099 void ShadowhandToCybergloveRemapper::jointstatesCallback( const sensor_msgs::JointStateConstPtr& msg )
00100 {
00101 sr_robot_msgs::joint joint;
00102 sr_robot_msgs::sendupdate pub;
00103
00104
00105 std::vector<double> vect = calibration_parser->get_remapped_vector(msg->position);
00106
00107 pub.sendupdate_length = number_hand_joints;
00108
00109 std::vector<sr_robot_msgs::joint> table(number_hand_joints);
00110 for( unsigned int i = 0; i < number_hand_joints; ++i )
00111 {
00112 joint.joint_name = joints_names[i];
00113 joint.joint_target = vect[i];
00114 table[i] = joint;
00115 }
00116 pub.sendupdate_length = number_hand_joints;
00117 pub.sendupdate_list = table;
00118 shadowhand_pub.publish(pub);
00119 }
00120 }