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