00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 """
00019 Minimizes the mapping matrix using a simplex algorithm
00020
00021 @author: Ugo Cupcic
00022 @contact: ugo@shadowrobot.com, contact@shadowrobot.com
00023 """
00024
00025 import roslib; roslib.load_manifest('sr_control_gui')
00026 import rospy
00027 from scipy.optimize import fmin
00028 from cyberglove_library import Cyberglove
00029
00030 class MappingConfiguration:
00031 def __init__(self, glove_data = [], hand_data = [], description = ""):
00032 self.glove_data = glove_data
00033 self.hand_data = hand_data
00034 self.description = description
00035
00036 def copy(self):
00037 tmp = MappingConfiguration(self.glove_data, self.hand_data, self.description)
00038 return tmp
00039
00040 class MappingMinimizer:
00041 def __init__(self, verbose = 1):
00042 rospy.init_node("cyberglove_mapper_minimizer")
00043
00044 self.cyberglove = Cyberglove()
00045
00046 self.verbose = verbose
00047
00048 glove_sensors = ["G_ThumbRotate", "G_ThumbMPJ", "G_ThumbIJ", "G_ThumbAb", "G_IndexMPJ", "G_IndexPIJ",
00049 "G_IndexDIJ", "G_MiddleMPJ", "G_MiddlePIJ", "G_MiddleDIJ", "G_MiddleIndexAb", "G_RingMPJ",
00050 "G_RingPIJ", "G_RingDIJ", "G_RingMiddleAb", "G_PinkieMPJ", "G_PinkiePIJ", "G_PinkieDIJ",
00051 "G_PinkieRingAb", "G_PalmArch", "G_WristPitch", "G_WristYaw"]
00052
00053 index = 0
00054 self.glove_name_index_map = {}
00055 for sensor in glove_sensors:
00056 self.glove_name_index_map[sensor] = index
00057 index += 1
00058
00059
00060 hand_joints = ["TH1","TH2","TH3","TH4","TH5","FF0","FF3","FF4","MF0","MF3","MF4","RF0","RF3","RF4","LF0",
00061 "LF3","LF4","LF5","WR1","WR2"]
00062
00063 index = 0
00064 self.hand_name_index_map = {}
00065 for sensor in hand_joints:
00066 self.hand_name_index_map[sensor] = index
00067 index += 1
00068
00069 self.thumb_glove = { "G_ThumbRotate": 0,
00070 "G_ThumbMPJ": 1,
00071 "G_ThumbAb": 2 }
00072
00073 self.thumb_hand = { "TH2": 0,
00074 "TH4": 1,
00075 "TH5": 2 }
00076
00077 self.configurations = []
00078 self.initialise_configurations()
00079
00080 self.simplex_iteration_index = 0
00081
00082 if(self.verbose == 1):
00083 for conf in self.configurations:
00084 print "-------"
00085 print conf.description
00086 print conf.glove_data
00087 print conf.hand_data
00088 print "-------"
00089 print ""
00090
00091 self.minerror = 1000000
00092 self.maxerror = 0
00093
00094 def initialise_configurations(self):
00095 configuration = MappingConfiguration()
00096
00097
00098
00099 configuration.description = "All fingers and thumb are curved maximum in a punch form ... "
00100 configuration.glove_data = []
00101
00102 configuration.hand_data = [[30.0, 52.0, 5.0],
00103 [30.0, 43.0, 0.0],
00104 [30.0, 68.0, 16.0]
00105 ]
00106
00107 self.configurations.append(configuration.copy())
00108
00109
00110
00111 configuration.description = "Thumb touching first finger tip ... "
00112 configuration.glove_data = []
00113
00114 configuration.hand_data = [[30.0, 54.0, -5.0],
00115 [19.0, 58.0, 28.0]]
00116
00117 self.configurations.append(configuration.copy())
00118
00119
00120
00121 configuration.description = "Thumb touching middle finger tip ... "
00122 configuration.glove_data = []
00123
00124 configuration.hand_data = [[30.0, 64.0, 9.0],
00125 [1.0, 68.0, 29.0]]
00126
00127 self.configurations.append(configuration.copy())
00128
00129
00130
00131 configuration.description = "Thumb touching ring finger tip ... "
00132 configuration.glove_data = []
00133
00134 configuration.hand_data = [[30.0, 75.0, 19.0],
00135 [1.0, 75.0, 42.0]]
00136
00137 self.configurations.append(configuration.copy())
00138
00139
00140
00141 configuration.description = "Thumb touching little finger tip ... "
00142 configuration.glove_data = []
00143
00144 configuration.hand_data = [[30.0, 75.0, 3.0],
00145 [1.0, 75.0, 35.0]]
00146
00147 self.configurations.append(configuration.copy())
00148
00149
00150
00151 configuration.description = "Thumb touching all the finger tips ... "
00152 configuration.glove_data = []
00153
00154 configuration.hand_data = [[-30.0, 75.0, 60.0],
00155 [-7.0, 63.0, 60.0]]
00156
00157 self.configurations.append(configuration.copy())
00158
00159
00160
00161 configuration.description = "hand flat, thumb relaxed along the fingers "
00162 configuration.glove_data = []
00163
00164 configuration.hand_data = [[0.0, 0.0, -60.0]]
00165
00166 self.configurations.append(configuration.copy())
00167
00168
00169
00170 configuration.description = "hand flat, thumb opened "
00171 configuration.glove_data = []
00172
00173 configuration.hand_data = [[0.0, 75.0, -60.0]]
00174
00175 self.configurations.append(configuration.copy())
00176
00177 def evaluation_function(self, matrix):
00178 """
00179 The error is computed by adding the square error for each configuration.
00180 """
00181 error = 0
00182
00183
00184 matrix_tmp = []
00185 for i in range(len(self.thumb_glove)):
00186 line = []
00187 for j in range(len(self.thumb_hand)):
00188 line.append(matrix[i*len(self.thumb_hand)+j])
00189 matrix_tmp.append(line)
00190
00191 matrix = matrix_tmp
00192 computed_vector_hand = []
00193
00194 for config in self.configurations:
00195
00196 for vec_glove in config.glove_data:
00197 computed_vector_hand.append(self.multiply(vec_glove, matrix))
00198
00199
00200 for vec_comp, vec_hand in zip(computed_vector_hand, config.hand_data):
00201 for computed_hand_data in vec_comp:
00202 for hand_data in vec_hand:
00203 error += (computed_hand_data-hand_data)*(computed_hand_data-hand_data)
00204
00205 if self.verbose == 1:
00206 print "error: "+str(error)
00207
00208 if error < self.minerror:
00209 self.minerror = error
00210
00211 if error > self.maxerror:
00212 self.maxerror = error
00213
00214 return error
00215
00216 def multiply(self, vector_glove, matrix):
00217 """
00218 multiply the vector by the matrix. Returns a vector.
00219 """
00220 vector_hand = []
00221 index_col = 0
00222 print vector_glove
00223 print matrix
00224 for glove_data in vector_glove:
00225 data = 0
00226 for line in matrix:
00227 data += (glove_data*line[index_col])
00228 vector_hand.append(data)
00229 index_col += 1
00230
00231 return vector_hand
00232
00233 def callback(self, xk):
00234 """
00235 Function called at each iteration
00236 """
00237 self.simplex_iteration_index += 1
00238 if self.simplex_iteration_index % 50 == 0:
00239 print "-------------------------"
00240 print "iteration number: "+ str(self.simplex_iteration_index)
00241
00242
00243 def minimize(self):
00244 start = []
00245 for i in range(0, len(self.thumb_hand)):
00246 line = []
00247 for j in range(0, len(self.thumb_glove)):
00248 line.append(0.1)
00249 start.append(line)
00250
00251
00252 xopt = fmin(self.evaluation_function, start, callback=self.callback, maxiter = 5000)
00253
00254
00255 output = []
00256 for i in range(len(self.thumb_glove)):
00257 line = []
00258 for j in range(len(self.thumb_hand)):
00259 line.append(xopt[i*len(self.thumb_hand)+j])
00260 output.append(line)
00261
00262 print "min error: "+ str(self.minerror)
00263 print "max error: "+ str(self.maxerror)
00264
00265 return output
00266
00267 def write_full_mapping(self, output_path = "../../../param/GloveToHandMappings"):
00268 """
00269 Writes the mapping matrix to a file:
00270 the glove values are the lines, the hand values are the columns
00271 """
00272
00273
00274 mapping_matrix = []
00275 for i in range(0, len(self.glove_name_index_map)):
00276 line = []
00277 for j in range(0, len(self.hand_name_index_map)):
00278 line.append(0.0)
00279 mapping_matrix.append(line)
00280
00281
00282
00283 mapping_matrix[self.glove_name_index_map["G_IndexDIJ"]][self.hand_name_index_map["FF0"]] = 1.0
00284 mapping_matrix[self.glove_name_index_map["G_IndexPIJ"]][self.hand_name_index_map["FF0"]] = 1.0
00285 mapping_matrix[self.glove_name_index_map["G_IndexMPJ"]][self.hand_name_index_map["FF3"]] = 1.0
00286 mapping_matrix[self.glove_name_index_map["G_MiddleIndexAb"]][self.hand_name_index_map["FF4"]] = -1.0
00287
00288 mapping_matrix[self.glove_name_index_map["G_MiddleDIJ"]][self.hand_name_index_map["MF0"]] = 1.0
00289 mapping_matrix[self.glove_name_index_map["G_MiddlePIJ"]][self.hand_name_index_map["MF0"]] = 1.0
00290 mapping_matrix[self.glove_name_index_map["G_MiddleMPJ"]][self.hand_name_index_map["MF3"]] = 1.0
00291 mapping_matrix[self.glove_name_index_map["G_RingMiddleAb"]][self.hand_name_index_map["MF4"]] = -1.0
00292
00293 mapping_matrix[self.glove_name_index_map["G_RingDIJ"]][self.hand_name_index_map["RF0"]] = 1.0
00294 mapping_matrix[self.glove_name_index_map["G_RingPIJ"]][self.hand_name_index_map["RF0"]] = 1.0
00295 mapping_matrix[self.glove_name_index_map["G_RingMPJ"]][self.hand_name_index_map["RF3"]] = 1.0
00296
00297 mapping_matrix[self.glove_name_index_map["G_PinkieDIJ"]][self.hand_name_index_map["LF0"]] = 1.0
00298 mapping_matrix[self.glove_name_index_map["G_PinkiePIJ"]][self.hand_name_index_map["LF0"]] = 1.0
00299 mapping_matrix[self.glove_name_index_map["G_PinkieMPJ"]][self.hand_name_index_map["LF3"]] = 1.0
00300 mapping_matrix[self.glove_name_index_map["G_PinkieRingAb"]][self.hand_name_index_map["LF4"]] = -1.0
00301 mapping_matrix[self.glove_name_index_map["G_PalmArch"]][self.hand_name_index_map["LF5"]] = 1.0
00302
00303 mapping_matrix[self.glove_name_index_map["G_WristPitch"]][self.hand_name_index_map["WR1"]] = 1.0
00304 mapping_matrix[self.glove_name_index_map["G_WristYaw"]][self.hand_name_index_map["WR2"]] = 1.0
00305
00306 mapping_matrix[self.glove_name_index_map["G_ThumbIJ"]][self.hand_name_index_map["TH1"]] = 1.0
00307
00308
00309
00310
00311
00312
00313
00314 thumb_mapping = self.minimize()
00315
00316
00317 for glove_name in self.thumb_glove.keys():
00318 for hand_name in self.thumb_hand.keys():
00319
00320 tmp_index_glove = self.thumb_glove[glove_name]
00321 tmp_index_hand = self.thumb_hand[hand_name]
00322
00323
00324 mapping_value = thumb_mapping[tmp_index_glove][tmp_index_hand]
00325
00326
00327 final_index_glove = self.glove_name_index_map[glove_name]
00328 final_index_hand = self.hand_name_index_map[hand_name]
00329
00330
00331 mapping_matrix[final_index_glove][final_index_hand] = mapping_value
00332
00333 file = open(output_path, "w")
00334 for line in mapping_matrix:
00335 for col in line:
00336 file.write(" "+str(col) )
00337 file.write("\n")
00338
00339 file.close()
00340
00341 def record(self, config):
00342 for i in range(0, 2):
00343 raw_input(str(i) + ": " + config.description)
00344 vector_data = [0] * len(self.thumb_glove)
00345 for sensor_name in self.thumb_glove.keys():
00346 data = self.cyberglove.read_calibrated_average_value(sensor_name)
00347 vector_data[self.thumb_glove[sensor_name]] = data
00348 config.glove_data.append(vector_data)
00349
00350 if(self.verbose == 1):
00351 print "read values:"
00352 print config.glove_data
00353
00354
00355
00356
00357
00358 def main():
00359 cyber_mapper = MappingMinimizer()
00360
00361 for config in cyber_mapper.configurations:
00362 cyber_mapper.record(config)
00363
00364 cyber_mapper.write_full_mapping()
00365
00366 return 0
00367
00368
00369
00370 if __name__ == "__main__":
00371 main()