18 Minimizes the mapping matrix using a simplex algorithm 21 @contact: ugo@shadowrobot.com, contact@shadowrobot.com 27 from scipy.optimize
import fmin
28 from cyberglove_library
import Cyberglove
33 def __init__(self, glove_data=[], hand_data=[], description=""):
47 rospy.init_node(
"cyberglove_mapper_minimizer")
54 "G_ThumbRotate",
"G_ThumbMPJ",
"G_ThumbIJ",
"G_ThumbAb",
"G_IndexMPJ",
"G_IndexPIJ",
55 "G_IndexDIJ",
"G_MiddleMPJ",
"G_MiddlePIJ",
"G_MiddleDIJ",
"G_MiddleIndexAb",
"G_RingMPJ",
56 "G_RingPIJ",
"G_RingDIJ",
"G_RingMiddleAb",
"G_PinkieMPJ",
"G_PinkiePIJ",
"G_PinkieDIJ",
57 "G_PinkieRingAb",
"G_PalmArch",
"G_WristPitch",
"G_WristYaw"]
61 for sensor
in glove_sensors:
67 "TH1",
"TH2",
"TH3",
"TH4",
"TH5",
"FF0",
"FF3",
"FF4",
"MF0",
"MF3",
"MF4",
"RF0",
"RF3",
"RF4",
"LF0",
68 "LF3",
"LF4",
"LF5",
"WR1",
"WR2"]
72 for sensor
in hand_joints:
92 print conf.description
106 configuration.description =
"All fingers and thumb are curved maximum in a punch form ... " 107 configuration.glove_data = []
109 configuration.hand_data = [[30.0, 52.0, 5.0],
114 self.configurations.append(configuration.copy())
118 configuration.description =
"Thumb touching first finger tip ... " 119 configuration.glove_data = []
121 configuration.hand_data = [[30.0, 54.0, -5.0],
124 self.configurations.append(configuration.copy())
128 configuration.description =
"Thumb touching middle finger tip ... " 129 configuration.glove_data = []
131 configuration.hand_data = [[30.0, 64.0, 9.0],
134 self.configurations.append(configuration.copy())
138 configuration.description =
"Thumb touching ring finger tip ... " 139 configuration.glove_data = []
141 configuration.hand_data = [[30.0, 75.0, 19.0],
144 self.configurations.append(configuration.copy())
148 configuration.description =
"Thumb touching little finger tip ... " 149 configuration.glove_data = []
151 configuration.hand_data = [[30.0, 75.0, 3.0],
154 self.configurations.append(configuration.copy())
158 configuration.description =
"Thumb touching all the finger tips ... " 159 configuration.glove_data = []
161 configuration.hand_data = [[-30.0, 75.0, 60.0],
164 self.configurations.append(configuration.copy())
168 configuration.description =
"hand flat, thumb relaxed along the fingers " 169 configuration.glove_data = []
171 configuration.hand_data = [[0.0, 0.0, -60.0]]
173 self.configurations.append(configuration.copy())
177 configuration.description =
"hand flat, thumb opened " 178 configuration.glove_data = []
180 configuration.hand_data = [[0.0, 75.0, -60.0]]
182 self.configurations.append(configuration.copy())
186 The error is computed by adding the square error for each configuration. 196 line.append(matrix[i * len(self.
thumb_hand) + j])
197 matrix_tmp.append(line)
200 computed_vector_hand = []
204 for vec_glove
in config.glove_data:
205 computed_vector_hand.append(self.
multiply(vec_glove, matrix))
208 for vec_comp, vec_hand
in zip(computed_vector_hand, config.hand_data):
209 for computed_hand_data
in vec_comp:
210 for hand_data
in vec_hand:
211 error += (computed_hand_data - hand_data) * (
212 computed_hand_data - hand_data)
215 print "error: " + str(error)
227 multiply the vector by the matrix. Returns a vector. 233 for glove_data
in vector_glove:
236 data += (glove_data * line[index_col])
237 vector_hand.append(data)
244 Function called at each iteration 248 print "-------------------------" 261 callback=self.
callback, maxiter=5000)
269 line.append(xopt[i * len(self.
thumb_hand) + j])
272 print "min error: " + str(self.
minerror)
273 print "max error: " + str(self.
maxerror)
279 Writes the mapping matrix to a file: 280 the glove values are the lines, the hand values are the columns 289 mapping_matrix.append(line)
346 for glove_name
in self.thumb_glove.keys():
347 for hand_name
in self.thumb_hand.keys():
353 mapping_value = thumb_mapping[tmp_index_glove][tmp_index_hand]
360 mapping_matrix[final_index_glove][
361 final_index_hand] = mapping_value
363 file = open(output_path,
"w")
364 for line
in mapping_matrix:
366 file.write(
" " + str(col))
372 for i
in range(0, 2):
373 raw_input(str(i) +
": " + config.description)
375 for sensor_name
in self.thumb_glove.keys():
376 data = self.cyberglove.read_calibrated_average_value(
379 config.glove_data.append(vector_data)
383 print config.glove_data
392 for config
in cyber_mapper.configurations:
393 cyber_mapper.record(config)
395 cyber_mapper.write_full_mapping()
401 if __name__ ==
"__main__":
def evaluation_function(self, matrix)
def __init__(self, verbose=1)
def __init__(self, glove_data=[], hand_data=[], description="")
def initialise_configurations(self)
def multiply(self, vector_glove, matrix)
def write_full_mapping(self, output_path="../../../param/GloveToHandMappings")