00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 """
00019 Calibration utility for the cyberglove.
00020
00021 @author: Ugo Cupcic
00022 @contact: ugo@shadowrobot.com, contact@shadowrobot.com
00023 """
00024 import roslib; roslib.load_manifest('sr_control_gui')
00025
00026 import os
00027 from cyberglove_library import Cyberglove
00028 from cyberglove.srv import Calibration as CalibrationSrv
00029
00030 import rospy
00031
00032 class Joint:
00033 """
00034 A class containing simple information regarding a joint: name, and calibrated value
00035 """
00036 def __init__(self, name, min=0, max = 90):
00037 """
00038 @param name: the name of the joint
00039 @param min: the min value to calibrate
00040 @param max: the max value to calibrate
00041 """
00042 self.name = name
00043 self.min = min
00044 self.max = max
00045
00046
00047 class CalibrationStep:
00048 """
00049 A class containing all the data for a given calibration step
00050 """
00051 def __init__(self, step_name="", step_description = [""], joints = []):
00052 """
00053 @param step_name: A short name for this calibration step
00054 @param step_description: A table containing 2 descriptions: the first one describes the min pose, the second
00055 the max
00056 @param joints: A table containing the joints to be calibrated
00057
00058 """
00059 self.step_name = step_name
00060 self.step_description = step_description
00061 self.joints = joints
00062
00063 class Calibration:
00064 """
00065 A class Containing all the calibration data for a given joint.
00066 """
00067 def __init__(self, raw_min = 0.0, raw_max= 0.0,
00068 calibrated_min = 0.0, calibrated_max= 0.0,
00069 is_calibrated = 0):
00070 self.raw_min = raw_min
00071 self.raw_max = raw_max
00072 self.calibrated_min = calibrated_min
00073 self.calibrated_max = calibrated_max
00074 self.is_calibrated = is_calibrated
00075
00076 def default_description(step_name, max = 0):
00077 """
00078 The default description function for a step. Just prints a text for each step.
00079
00080 @param step_name: the name of the step
00081 @param max: if 0=>we're reading the min values, if 1=> max values
00082 """
00083 if max == 0:
00084 print "calibrating min values for: "+ str(step_name)
00085 else:
00086 print "calibrating max values for: "+ str(step_name)
00087
00088 def do_nothing(step_name, max = 0):
00089 """
00090 A function that does nothing. Used to have an empty description function.
00091 """
00092 nothing = True
00093
00094 class CybergloveCalibrer:
00095 """
00096 A utility to calibrate the cyberglove.
00097 """
00098 def __init__(self, description_function = default_description):
00099 """
00100 Initialize some class variables: a table containing the calibration steps, a connection to the cyberglove
00101 library and a description function for the calibration steps
00102
00103 @param description_function: specify a function you want to use to describe the calibration steps ( text /
00104 pictures / animation / ... ). Must take a joint name as parameter.
00105 """
00106 self.calibration_steps = []
00107
00108 self.cyberglove = Cyberglove()
00109
00110
00111 self.joints = {}
00112 for name in self.cyberglove.get_joints_names():
00113 self.joints[name] = Calibration()
00114
00115 self.get_calibration_steps()
00116
00117 if description_function == None:
00118 description_function = do_nothing
00119 self.description_function = description_function
00120
00121 def get_calibration_steps(self):
00122 """
00123 Read the calibration steps from the xml file.
00124
00125 @return: 0 when the values were read.
00126 """
00127
00128
00129 joints1 = [Joint("G_IndexMPJ", 0, 90), Joint("G_IndexPIJ", 0, 90), Joint("G_IndexDIJ", 0, 90),
00130 Joint("G_MiddleMPJ", 0, 90), Joint("G_MiddlePIJ", 0, 90), Joint("G_MiddleDIJ", 0, 90),
00131 Joint("G_RingMPJ", 0, 90), Joint("G_RingPIJ", 0, 90), Joint("G_RingDIJ", 0, 90),
00132 Joint("G_PinkieMPJ", 0, 90), Joint("G_PinkiePIJ", 0, 90), Joint("G_PinkieDIJ", 0, 90),
00133 Joint("G_ThumbAb", 50, 0) ]
00134 self.calibration_steps.append(CalibrationStep(step_name="Joints 0s, 3s and thumb abduction (THJ4)",
00135 step_description = ["Hand flat on a table, fingers joined, thumb opened",
00136 "Hand forming a fist, thumb closed"],
00137 joints = joints1 ))
00138
00139
00140 joints2 = [Joint("G_ThumbIJ", 90, 0), Joint("G_ThumbMPJ", 30, -30),
00141 Joint("G_MiddleIndexAb", 0, 50), Joint("G_RingMiddleAb", 0, 50), Joint("G_PinkieRingAb", 0, 50),
00142 Joint("G_WristYaw", 10, -30)]
00143 self.calibration_steps.append(CalibrationStep(step_name="Joints 4s + TH1, 2, and WR2",
00144 step_description = ["Hand flat fingers joined, thumb completely curled under the palm, wrist 2 bent to the left",
00145 "Hand flat fingers apart, thumb completely opened, wrist bent 2 to the right"],
00146 joints = joints2 ))
00147
00148
00149 joints3 = [Joint("G_ThumbRotate", 60, -60)]
00150 self.calibration_steps.append(CalibrationStep(step_name="Joint TH5",
00151 step_description = ["thumb completely under the palm",
00152 "thumb completely opened, curled over the palm"],
00153 joints = joints3 ))
00154
00155
00156 joints4 = [Joint("G_PalmArch", 0, 40), Joint("G_WristPitch", -30, 40)]
00157 self.calibration_steps.append(CalibrationStep(step_name="LF5 and WR1",
00158 step_description = ["Hand flat, wrist 1 bent backward",
00159 "Palm curled (LFJ5), wrist 1 bent forward"],
00160 joints = joints4 ))
00161
00162 return 0
00163
00164 def do_step_min(self, index):
00165 """
00166 Run the given step of the calibration, gets the min values.
00167
00168 @param index: the index of the step in the calibration file
00169 @return: 0 when the values were read.
00170 """
00171 joints = self.calibration_steps[index].joints
00172
00173 self.description_function(self.calibration_steps[index].step_description[0], 0)
00174
00175 for joint in joints:
00176 name = joint.name
00177
00178 self.joints[name].raw_min = self.cyberglove.read_raw_average_value(name)
00179 self.joints[name].calibrated_min = joint.min
00180
00181 self.joints[name].is_calibrated += 0.5
00182 return 0
00183
00184 def do_step_max(self, index):
00185 """
00186 Run the given step of the calibration, gets the max values.
00187 As this method is called after the do_step_min() method, we don't display the description
00188
00189 @param index: the index of the step in the calibration file
00190 @return: 0 when the values were read.
00191 """
00192 joints = self.calibration_steps[index].joints
00193
00194 self.description_function(self.calibration_steps[index].step_description[1], 0)
00195
00196 for joint in joints:
00197 name = joint.name
00198
00199 self.joints[name].raw_max = self.cyberglove.read_raw_average_value(name)
00200 self.joints[name].calibrated_max = joint.max
00201
00202 self.joints[name].is_calibrated += 0.5
00203 return 0
00204
00205 def is_step_done(self, joint_name):
00206 """
00207 Check if the joint is calibrated.
00208
00209 @param joint_name: the name of the joint
00210 @return: 1 if the joint has already been calibrated.
00211 """
00212
00213 return self.joints[joint_name].is_calibrated
00214
00215 def all_steps_done(self):
00216 """
00217 Check if all the steps were processed.
00218
00219 @return: True if all the steps were processed.
00220 """
00221 for calib in self.joints.values():
00222 if calib.is_calibrated != 1:
00223 return False
00224
00225 return True
00226
00227 def reorder_calibration(self):
00228 """
00229 Reorder the calibration: set the raw_min to the min raw_value
00230 """
00231 for name in self.joints.keys():
00232 if self.joints[name].raw_min > self.joints[name].raw_max:
00233 tmp_raw = self.joints[name].raw_min
00234 tmp_cal = self.joints[name].calibrated_min
00235 self.joints[name].raw_min = self.joints[name].raw_max
00236 self.joints[name].calibrated_min = self.joints[name].calibrated_max
00237 self.joints[name].raw_max = tmp_raw
00238 self.joints[name].calibrated_max = tmp_cal
00239
00240 def write_calibration_file(self, filepath):
00241 """
00242 Checks if all the steps were processed by calling self.all_steps_done()
00243 Reorder the calibration
00244 Then writes the whole calibration to a given file.
00245
00246 @param filepath: Where to write the calibration
00247 @return: 0 if the file has been written,
00248 -1 if the calibration is not finished yet,
00249 -2 if other error
00250 """
00251
00252
00253 if not self.all_steps_done():
00254 return -1
00255
00256
00257 self.reorder_calibration()
00258
00259
00260
00261
00262
00263 text = []
00264
00265 text.append("<?xml version=\"1.0\" ?>")
00266 text.append("<Cyberglove_calibration>")
00267 for name in self.joints:
00268
00269 text.append("<Joint name=\""+name+"\">")
00270
00271 cal = self.joints[name]
00272
00273 text.append("<calib raw_value=\""+str(cal.raw_min)
00274 +"\" calibrated_value=\""
00275 +str(cal.calibrated_min)+"\"/>")
00276
00277
00278 text.append("<calib raw_value=\""+str(cal.raw_max)
00279 +"\" calibrated_value=\""
00280 +str(cal.calibrated_max)+"\"/>")
00281
00282 text.append("</Joint>")
00283
00284 text.append("</Cyberglove_calibration>")
00285
00286
00287 try:
00288 output = open(filepath, "w")
00289 for line in text:
00290 output.write(line+"\n")
00291
00292 output.close()
00293 except:
00294 return -2
00295
00296 return 0
00297
00298 def load_calib(self, filename):
00299 if filename == "":
00300 return -1
00301
00302 rospy.wait_for_service('/cyberglove/calibration')
00303 try:
00304 calib = rospy.ServiceProxy('cyberglove/calibration', CalibrationSrv)
00305 path = filename.encode("iso-8859-1")
00306 resp = calib(path)
00307 return resp.state
00308 except rospy.ServiceException, e:
00309 print 'Failed to call start service'
00310 return -2
00311
00312
00313
00314
00315
00316
00317 def main():
00318 cyber_calib = CybergloveCalibrer()
00319 for i in range(0, len(cyber_calib.calibration_steps)):
00320 raw_input(cyber_calib.calibration_steps[i].step_description[0])
00321 cyber_calib.do_step_min(i)
00322 raw_input(cyber_calib.calibration_steps[i].step_description[1])
00323
00324 cyber_calib.do_step_max(i)
00325 error = cyber_calib.write_calibration_file("../../param/cyberglove.cal")
00326 print error
00327
00328 return 0
00329
00330
00331
00332 if __name__ == "__main__":
00333 main()