cyberglove_mapper.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2011 Shadow Robot Company Ltd.
4 #
5 # This program is free software: you can redistribute it and/or modify it
6 # under the terms of the GNU General Public License as published by the Free
7 # Software Foundation version 2 of the License.
8 #
9 # This program is distributed in the hope that it will be useful, but WITHOUT
10 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
11 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
12 # more details.
13 #
14 # You should have received a copy of the GNU General Public License along
15 # with this program. If not, see <http://www.gnu.org/licenses/>.
16 #
17 """
18 Minimizes the mapping matrix using a simplex algorithm
19 
20 @author: Ugo Cupcic
21 @contact: ugo@shadowrobot.com, contact@shadowrobot.com
22 """
23 
24 import roslib
25 
26 import rospy
27 from scipy.optimize import fmin
28 from cyberglove_library import Cyberglove
29 
30 
32 
33  def __init__(self, glove_data=[], hand_data=[], description=""):
34  self.glove_data = glove_data
35  self.hand_data = hand_data
36  self.description = description
37 
38  def copy(self):
40  self.glove_data, self.hand_data, self.description)
41  return tmp
42 
43 
45 
46  def __init__(self, verbose=1):
47  rospy.init_node("cyberglove_mapper_minimizer")
48  # connect to the cyberglove
49  self.cyberglove = Cyberglove()
50 
51  self.verbose = verbose
52 
53  glove_sensors = [
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"]
58 
59  index = 0
61  for sensor in glove_sensors:
62  self.glove_name_index_map[sensor] = index
63  index += 1
64 
65  # fill the table containing all the joints
66  hand_joints = [
67  "TH1", "TH2", "TH3", "TH4", "TH5", "FF0", "FF3", "FF4", "MF0", "MF3", "MF4", "RF0", "RF3", "RF4", "LF0",
68  "LF3", "LF4", "LF5", "WR1", "WR2"]
69 
70  index = 0
72  for sensor in hand_joints:
73  self.hand_name_index_map[sensor] = index
74  index += 1
75 
76  self.thumb_glove = {"G_ThumbRotate": 0,
77  "G_ThumbMPJ": 1,
78  "G_ThumbAb": 2}
79 
80  self.thumb_hand = {"TH2": 0,
81  "TH4": 1,
82  "TH5": 2}
83 
84  self.configurations = []
86 
88 
89  if(self.verbose == 1):
90  for conf in self.configurations:
91  print "-------"
92  print conf.description
93  print conf.glove_data
94  print conf.hand_data
95  print "-------"
96  print ""
97 
98  self.minerror = 1000000
99  self.maxerror = 0
100 
102  configuration = MappingConfiguration()
103 
104  #
105  # First configuration
106  configuration.description = "All fingers and thumb are curved maximum in a punch form ... "
107  configuration.glove_data = []
108  # corresponding data for the hand
109  configuration.hand_data = [[30.0, 52.0, 5.0],
110  [30.0, 43.0, 0.0],
111  [30.0, 68.0, 16.0]
112  ]
113 
114  self.configurations.append(configuration.copy())
115 
116  #
117  # Second configuration
118  configuration.description = "Thumb touching first finger tip ... "
119  configuration.glove_data = []
120  # corresponding data for the hand
121  configuration.hand_data = [[30.0, 54.0, -5.0],
122  [19.0, 58.0, 28.0]]
123 
124  self.configurations.append(configuration.copy())
125 
126  #
127  # Third configuration
128  configuration.description = "Thumb touching middle finger tip ... "
129  configuration.glove_data = []
130  # corresponding data for the hand
131  configuration.hand_data = [[30.0, 64.0, 9.0],
132  [1.0, 68.0, 29.0]]
133 
134  self.configurations.append(configuration.copy())
135 
136  #
137  # Fourth configuration
138  configuration.description = "Thumb touching ring finger tip ... "
139  configuration.glove_data = []
140  # corresponding data for the hand
141  configuration.hand_data = [[30.0, 75.0, 19.0],
142  [1.0, 75.0, 42.0]]
143 
144  self.configurations.append(configuration.copy())
145 
146  #
147  # Fifth configuration
148  configuration.description = "Thumb touching little finger tip ... "
149  configuration.glove_data = []
150  # corresponding data for the hand
151  configuration.hand_data = [[30.0, 75.0, 3.0],
152  [1.0, 75.0, 35.0]]
153 
154  self.configurations.append(configuration.copy())
155 
156  #
157  # Sixth configuration
158  configuration.description = "Thumb touching all the finger tips ... "
159  configuration.glove_data = []
160  # corresponding data for the hand
161  configuration.hand_data = [[-30.0, 75.0, 60.0],
162  [-7.0, 63.0, 60.0]]
163 
164  self.configurations.append(configuration.copy())
165 
166  #
167  # Seventh configuration
168  configuration.description = "hand flat, thumb relaxed along the fingers "
169  configuration.glove_data = []
170  # corresponding data for the hand
171  configuration.hand_data = [[0.0, 0.0, -60.0]]
172 
173  self.configurations.append(configuration.copy())
174 
175  #
176  # Eigth configuration
177  configuration.description = "hand flat, thumb opened "
178  configuration.glove_data = []
179  # corresponding data for the hand
180  configuration.hand_data = [[0.0, 75.0, -60.0]]
181 
182  self.configurations.append(configuration.copy())
183 
184  def evaluation_function(self, matrix):
185  """
186  The error is computed by adding the square error for each configuration.
187  """
188  error = 0
189 
190  # rebuild the matrix as a matrix, not a vector (the implementation of
191  # the simplex in scipy works on vectors
192  matrix_tmp = []
193  for i in range(len(self.thumb_glove)):
194  line = []
195  for j in range(len(self.thumb_hand)):
196  line.append(matrix[i * len(self.thumb_hand) + j])
197  matrix_tmp.append(line)
198 
199  matrix = matrix_tmp
200  computed_vector_hand = []
201 
202  for config in self.configurations:
203  # get the hand vectors from the glove data
204  for vec_glove in config.glove_data:
205  computed_vector_hand.append(self.multiply(vec_glove, matrix))
206 
207  # compute the square error
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)
213 
214  if self.verbose == 1:
215  print "error: " + str(error)
216 
217  if error < self.minerror:
218  self.minerror = error
219 
220  if error > self.maxerror:
221  self.maxerror = error
222 
223  return error
224 
225  def multiply(self, vector_glove, matrix):
226  """
227  multiply the vector by the matrix. Returns a vector.
228  """
229  vector_hand = []
230  index_col = 0
231  print vector_glove
232  print matrix
233  for glove_data in vector_glove:
234  data = 0
235  for line in matrix:
236  data += (glove_data * line[index_col])
237  vector_hand.append(data)
238  index_col += 1
239 
240  return vector_hand
241 
242  def callback(self, xk):
243  """
244  Function called at each iteration
245  """
246  self.simplex_iteration_index += 1
247  if self.simplex_iteration_index % 50 == 0:
248  print "-------------------------"
249  print "iteration number: " + str(self.simplex_iteration_index)
250  # print xk
251 
252  def minimize(self):
253  start = []
254  for i in range(0, len(self.thumb_hand)):
255  line = []
256  for j in range(0, len(self.thumb_glove)):
257  line.append(0.1)
258  start.append(line)
259 
260  xopt = fmin(self.evaluation_function, start,
261  callback=self.callback, maxiter=5000)
262 
263  # rebuild the result as a matrix, not a vector (the implementation of
264  # the simplex in scipy works on vectors
265  output = []
266  for i in range(len(self.thumb_glove)):
267  line = []
268  for j in range(len(self.thumb_hand)):
269  line.append(xopt[i * len(self.thumb_hand) + j])
270  output.append(line)
271 
272  print "min error: " + str(self.minerror)
273  print "max error: " + str(self.maxerror)
274 
275  return output
276 
277  def write_full_mapping(self, output_path="../../../param/GloveToHandMappings"):
278  """
279  Writes the mapping matrix to a file:
280  the glove values are the lines, the hand values are the columns
281  """
282 
283  # initialise the matrix with 0s
284  mapping_matrix = []
285  for i in range(0, len(self.glove_name_index_map)):
286  line = []
287  for j in range(0, len(self.hand_name_index_map)):
288  line.append(0.0)
289  mapping_matrix.append(line)
290 
291  # TH3 is always 0, RF4 as well
292  # fill the matrix with the known values + th1 (all except the thumb)
293  mapping_matrix[self.glove_name_index_map["G_IndexDIJ"]][
294  self.hand_name_index_map["FF0"]] = 1.0
295  mapping_matrix[self.glove_name_index_map["G_IndexPIJ"]][
296  self.hand_name_index_map["FF0"]] = 1.0
297  mapping_matrix[self.glove_name_index_map["G_IndexMPJ"]][
298  self.hand_name_index_map["FF3"]] = 1.0
299  mapping_matrix[self.glove_name_index_map["G_MiddleIndexAb"]][
300  self.hand_name_index_map["FF4"]] = -1.0
301 
302  mapping_matrix[self.glove_name_index_map["G_MiddleDIJ"]][
303  self.hand_name_index_map["MF0"]] = 1.0
304  mapping_matrix[self.glove_name_index_map["G_MiddlePIJ"]][
305  self.hand_name_index_map["MF0"]] = 1.0
306  mapping_matrix[self.glove_name_index_map["G_MiddleMPJ"]][
307  self.hand_name_index_map["MF3"]] = 1.0
308  mapping_matrix[self.glove_name_index_map["G_RingMiddleAb"]][
309  self.hand_name_index_map["MF4"]] = -1.0
310 
311  mapping_matrix[self.glove_name_index_map["G_RingDIJ"]][
312  self.hand_name_index_map["RF0"]] = 1.0
313  mapping_matrix[self.glove_name_index_map["G_RingPIJ"]][
314  self.hand_name_index_map["RF0"]] = 1.0
315  mapping_matrix[self.glove_name_index_map["G_RingMPJ"]][
316  self.hand_name_index_map["RF3"]] = 1.0
317 
318  mapping_matrix[self.glove_name_index_map["G_PinkieDIJ"]][
319  self.hand_name_index_map["LF0"]] = 1.0
320  mapping_matrix[self.glove_name_index_map["G_PinkiePIJ"]][
321  self.hand_name_index_map["LF0"]] = 1.0
322  mapping_matrix[self.glove_name_index_map["G_PinkieMPJ"]][
323  self.hand_name_index_map["LF3"]] = 1.0
324  mapping_matrix[self.glove_name_index_map["G_PinkieRingAb"]][
325  self.hand_name_index_map["LF4"]] = -1.0
326  mapping_matrix[self.glove_name_index_map["G_PalmArch"]][
327  self.hand_name_index_map["LF5"]] = 1.0
328 
329  mapping_matrix[self.glove_name_index_map["G_WristPitch"]][
330  self.hand_name_index_map["WR1"]] = 1.0
331  mapping_matrix[self.glove_name_index_map["G_WristYaw"]][
332  self.hand_name_index_map["WR2"]] = 1.0
333 
334  mapping_matrix[self.glove_name_index_map["G_ThumbIJ"]][
335  self.hand_name_index_map["TH1"]] = 1.0
336 
337  # mapping_matrix[self.glove_name_index_map["G_ThumbAb"]][self.hand_name_index_map["TH4"]] = 1.0
338  # mapping_matrix[self.glove_name_index_map["G_ThumbRotate"]][self.hand_name_index_map["TH5"]] = 1.0
339  # mapping_matrix[self.glove_name_index_map["G_ThumbMPJ"]][self.hand_name_index_map["TH2"]]
340  # = 1.0
341 
342  # compute the best mapping for the thumb except th1
343  thumb_mapping = self.minimize()
344 
345  # fill the matrix with the thumb values computed with the simplex
346  for glove_name in self.thumb_glove.keys():
347  for hand_name in self.thumb_hand.keys():
348  # indexes in the computed thumb mapping matrix
349  tmp_index_glove = self.thumb_glove[glove_name]
350  tmp_index_hand = self.thumb_hand[hand_name]
351 
352  # retrieve the mapping value for those sensors
353  mapping_value = thumb_mapping[tmp_index_glove][tmp_index_hand]
354 
355  # indexes for the whole mapping matrix
356  final_index_glove = self.glove_name_index_map[glove_name]
357  final_index_hand = self.hand_name_index_map[hand_name]
358 
359  # update matrix
360  mapping_matrix[final_index_glove][
361  final_index_hand] = mapping_value
362  # write the matrix to a file
363  file = open(output_path, "w")
364  for line in mapping_matrix:
365  for col in line:
366  file.write(" " + str(col))
367  file.write("\n")
368 
369  file.close()
370 
371  def record(self, config):
372  for i in range(0, 2):
373  raw_input(str(i) + ": " + config.description)
374  vector_data = [0] * len(self.thumb_glove)
375  for sensor_name in self.thumb_glove.keys():
376  data = self.cyberglove.read_calibrated_average_value(
377  sensor_name)
378  vector_data[self.thumb_glove[sensor_name]] = data
379  config.glove_data.append(vector_data)
380 
381  if(self.verbose == 1):
382  print "read values:"
383  print config.glove_data
384 
385 
386 #
387 # MAIN #
388 #
389 def main():
390  cyber_mapper = MappingMinimizer()
391 
392  for config in cyber_mapper.configurations:
393  cyber_mapper.record(config)
394 
395  cyber_mapper.write_full_mapping()
396 
397  return 0
398 
399 
400 # start the script
401 if __name__ == "__main__":
402  main()
def __init__(self, glove_data=[], hand_data=[], description="")
def write_full_mapping(self, output_path="../../../param/GloveToHandMappings")


sr_gui_cyberglove_calibrator
Author(s): Ugo Cupcic
autogenerated on Wed Oct 14 2020 03:22:50