00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 import roslib
00020
00021 import time
00022 import os
00023 import math
00024 import rospy
00025 import subprocess
00026 import threading
00027 import rosgraph.masterapi
00028 from sr_robot_msgs.msg import sendupdate, joint, joints_data
00029 from sensor_msgs.msg import *
00030
00031
00032 class Joint():
00033
00034 def __init__(self, name="", motor="", min=0, max=90):
00035 self.name = name
00036 self.motor = motor
00037 self.min = min
00038 self.max = max
00039
00040
00041 class Cyberglove:
00042
00043 """
00044 Interface to the Cyberglove publisher.
00045 """
00046
00047 def __init__(self, max_values=2):
00048 self.joints = {"G_ThumbRotate": Joint(),
00049 "G_ThumbMPJ": Joint(),
00050 "G_ThumbIJ": Joint(),
00051 "G_ThumbAb": Joint(),
00052 "G_IndexMPJ": Joint(),
00053 "G_IndexPIJ": Joint(),
00054 "G_IndexDIJ": Joint(),
00055 "G_MiddleMPJ": Joint(),
00056 "G_MiddlePIJ": Joint(),
00057 "G_MiddleDIJ": Joint(),
00058 "G_MiddleIndexAb": Joint(),
00059 "G_RingMPJ": Joint(),
00060 "G_RingPIJ": Joint(),
00061 "G_RingDIJ": Joint(),
00062 "G_RingMiddleAb": Joint(),
00063 "G_PinkieMPJ": Joint(),
00064 "G_PinkiePIJ": Joint(),
00065 "G_PinkieDIJ": Joint(),
00066 "G_PinkieRingAb": Joint(),
00067 "G_PalmArch": Joint(),
00068 "G_WristPitch": Joint(),
00069 "G_WristYaw": Joint()}
00070
00071 self.raw_messages = []
00072 self.calibrated_messages = []
00073 self.max_values = max_values
00074 self.map = {}
00075 self.hasglove = 0
00076 self.isFirstMessage = True
00077 self.liste = 0
00078 self.raw = rospy.Subscriber(
00079 'cyberglove/raw/joint_states', JointState, self.callback_raw)
00080 self.calibrated = rospy.Subscriber(
00081 'cyberglove/calibrated/joint_states', JointState, self.callback_calibrated)
00082 threading.Thread(None, rospy.spin)
00083 if self.has_glove():
00084 time.sleep(1.0)
00085 self.createMap()
00086 else:
00087 raise Exception("No glove found")
00088
00089 def callback_raw(self, data):
00090 """
00091 Adds the last values received to the list of raw values
00092 @param data: the message which called the callback
00093 """
00094 self.addValue(self.raw_messages, data)
00095
00096 def callback_calibrated(self, data):
00097 """
00098 Adds the last values received to the list of calibrated values
00099 @param data: the message which called the callback
00100 """
00101 self.addValue(self.calibrated_messages, data)
00102
00103 def addValue(self, vector, value):
00104 """
00105 Fills a vector with the received values, and replaces the old values
00106 when the vector is full
00107 @param vector : the vector to fill (raw or calibrated)
00108 @param value : the value to add
00109 """
00110 if len(vector) < self.max_values:
00111 vector.append(value)
00112 else:
00113 vector.pop(0)
00114 vector.append(value)
00115
00116 def createMap(self):
00117 """
00118 Maps the name of the joints to their index in the message
00119 """
00120
00121 for index in range(0, len(self.raw_messages[0].name)):
00122 self.map[self.raw_messages[0].name[index]] = index
00123
00124 def read_raw_average_value(self, joint_name):
00125 """
00126 return the raw value of a given joint
00127
00128 @param joint_name: the name of the glove of the Cyberglove
00129 """
00130 raw_value = 0
00131 joint_index = self.map[joint_name]
00132 for index in range(0, len(self.raw_messages)):
00133 raw_value = raw_value + \
00134 self.raw_messages[index].position[joint_index]
00135
00136 raw_value = raw_value / len(self.raw_messages)
00137
00138 return raw_value
00139
00140 def read_calibrated_average_value(self, joint_name):
00141 """
00142 return the current positions for the given joint_name
00143
00144 @param joint_name: the name of the joint
00145 @return: the corresponding position
00146 """
00147
00148 calibrated_value = 0
00149
00150 joint_index = self.map[joint_name]
00151 for index in range(0, len(self.calibrated_messages)):
00152 calibrated_value = calibrated_value + \
00153 self.calibrated_messages[index].position[joint_index]
00154
00155 calibrated_value = calibrated_value / len(self.calibrated_messages)
00156
00157 return calibrated_value
00158
00159 def get_joints_names(self):
00160 """
00161 Return an array containing the Cyberglove joints names
00162
00163 @return: the joints names array
00164 """
00165 return self.joints.keys()
00166
00167 def has_glove(self):
00168 """
00169 @return: True if a cyberglove is detected by ROS
00170 """
00171 if not self.hasglove == 0:
00172 return self.hasglove
00173 self.hasglove = False
00174 if self.liste == 0:
00175 master = rosgraph.masterapi.Master('rostopic list')
00176 self.liste = master.getPublishedTopics('')
00177
00178 for topic_typ in self.liste:
00179 for topic in topic_typ:
00180 if '/calibrated' in topic:
00181 self.hasglove = True
00182 return self.hasglove