generate_all_test_pattern.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # 1. estimation_config.launch
4 # i) include leg or not, bool
5 # ii) use chain in 2nd calibration, bool
6 # iii) calibrate joint or not, bool
7 
8 # 2. free_cb_locations.yaml
9 # i) include leg or not, bool
10 
11 # 3. free_cameras.yaml
12 # i) include leg
13 # ii) include arm
14 
15 # we have 6 boolean parameters...
16 
17 # 4. free_arms.yaml
18 # * which joint to calibrate
19 
20 import os
21 import sys
22 import shutil
23 import stat
24 import re
25 from multiprocessing import Pool
26 import multiprocessing
27 import subprocess
28 import time
29 JOINT_NAMES = ["LARM_JOINT0", "LARM_JOINT1", "LARM_JOINT2", "LARM_JOINT3", "LARM_JOINT4", "LARM_JOINT5", "LARM_JOINT6", "LARM_JOINT7",
30  "RARM_JOINT0", "RARM_JOINT1", "RARM_JOINT2", "RARM_JOINT3", "RARM_JOINT4", "RARM_JOINT5", "RARM_JOINT6", "RARM_JOINT7",
31  "HEAD_JOINT0", "HEAD_JOINT1",
32  "CHEST_JOINT0", "CHEST_JOINT1"]
33 
34 counter = 1
35 
36 def replaceStringWithDict(format, variables):
37  for (key, val) in variables.items():
38  format = format.replace("${" + key + "}", str(val))
39  return format
40 
41 def generateEstimationConfig(root_dir,
42  estimation_config_include_leg,
43  estimation_config_use_chain,
44  estimation_config_calibrate_joint):
45  file_string = """
46  <launch>
47 
48  <group ns="calibration_config" clear_params="true">
49  <rosparam file="$(find jsk_calibration)/staro_calibration/estimate_params/test_all/${root_dir}/config/system.yaml" command="load" />
50 
51  <group ns="cal_steps">
52 
53  <group ns="staro - 00 - Estimating Checkerboard Locations">
54  <param name="free_params" textfile="$(find jsk_calibration)/staro_calibration/estimate_params/test_all/${root_dir}/config/free_cb_locations.yaml" />
55  <param name="use_cov" type="bool" value="False" />
56  <rosparam if="${estimation_config_include_leg}">
57  sensors:
58  - LARM_chain
59  - RARM_chain
60  - LLEG_chain
61  - RLEG_chain
62  - head_camera
63  </rosparam>
64  <rosparam unless="${estimation_config_include_leg}">
65  sensors:
66  - LARM_chain
67  - RARM_chain
68  - head_camera
69  </rosparam>
70  <param name="output_filename" type="string" value="config_0" />
71  </group>
72 
73  <group ns="staro - 01 - Adding Camera Locations">
74  <param name="free_params" textfile="$(find jsk_calibration)/staro_calibration/estimate_params/test_all/${root_dir}/config/free_cameras.yaml" />
75  <param name="use_cov" type="bool" value="True" />
76  <group if="${estimation_config_use_chain}">
77  <rosparam if="${estimation_config_include_leg}">
78  sensors:
79  - LARM_chain
80  - RARM_chain
81  - LLEG_chain
82  - RLEG_chain
83  - head_camera
84  </rosparam>
85  <rosparam unless="${estimation_config_include_leg}">
86  sensors:
87  - LARM_chain
88  - RARM_chain
89  - head_camera
90  </rosparam>
91  </group>
92  <group unless="${estimation_config_use_chain}">
93  <rosparam>
94  sensors:
95  - head_camera
96  </rosparam>
97  </group>
98  <param name="output_filename" type="string" value="config_1" if="${estimation_config_calibrate_joint}"/>
99  <param name="output_filename" type="string" value="system_calibrated" unless="${estimation_config_calibrate_joint}"/>
100  </group>
101  <group ns="staro - 02 - Joint Offset" if="${estimation_config_calibrate_joint}">
102  <param name="free_params" textfile="$(find jsk_calibration)/staro_calibration/estimate_params/test_all/${root_dir}/config/free_arms.yaml" />
103  <param name="use_cov" type="bool" value="True" />
104  <rosparam>
105  sensors:
106  - LARM_chain
107  - RARM_chain
108  - LLEG_chain
109  - RLEG_chain
110  - head_camera
111  </rosparam>
112  <param name="output_filename" type="string" value="system_calibrated" />
113  </group>
114 
115  </group>
116 
117  </group>
118 
119 </launch>
120 """
121  replaced_str = replaceStringWithDict(file_string, {
122  "root_dir": root_dir,
123  "estimation_config_include_leg": estimation_config_include_leg,
124  "estimation_config_use_chain": estimation_config_use_chain,
125  "estimation_config_calibrate_joint": estimation_config_calibrate_joint})
126  file_path = os.path.join(root_dir, "estimation_config.launch")
127  with open(file_path, "w") as f:
128  f.write(replaced_str)
129 
130 
131 def generateFreeCBLocations(root_name,
132  free_cb_locations_use_leg):
133  if free_cb_locations_use_leg:
134  file_string = """
135  transforms:
136  LARM_chain_cb: [1, 1, 1, 1, 1, 1]
137  RARM_chain_cb: [1, 1, 1, 1, 1, 1]
138  LLEG_chain_cb: [1, 1, 1, 1, 1, 1]
139  RLEG_chain_cb: [1, 1, 1, 1, 1, 1]
140 
141  chains:
142  LARM_chain:
143  gearing: [0, 0, 0, 0, 0, 0]
144  RARM_chain:
145  gearing: [0, 0, 0, 0, 0, 0]
146  LLEG_chain:
147  gearing: [0, 0, 0, 0, 0, 0]
148  RLEG_chain:
149  gearing: [0, 0, 0, 0, 0, 0]
150  head_chain:
151  gearing: [0, 0]
152  torso_chain:
153  gearing: [0, 0]
154 
155 
156  rectified_cams:
157  head_camera:
158  baseline_shift: 0
159  f_shift: 0
160  cx_shift: 0
161  cy_shift: 0
162 
163  tilting_lasers: {}
164 
165  checkerboards:
166  mmurooka_board:
167  spacing_x: 0.0
168  spacing_y: 0.0
169 """
170  else:
171  file_string = """
172  transforms:
173  LARM_chain_cb: [1, 1, 1, 1, 1, 1]
174  RARM_chain_cb: [1, 1, 1, 1, 1, 1]
175 
176  chains:
177  LARM_chain:
178  gearing: [0, 0, 0, 0, 0, 0]
179  RARM_chain:
180  gearing: [0, 0, 0, 0, 0, 0]
181  LLEG_chain:
182  gearing: [0, 0, 0, 0, 0, 0]
183  RLEG_chain:
184  gearing: [0, 0, 0, 0, 0, 0]
185  head_chain:
186  gearing: [0, 0]
187  torso_chain:
188  gearing: [0, 0]
189 
190 
191  rectified_cams:
192  head_camera:
193  baseline_shift: 0
194  f_shift: 0
195  cx_shift: 0
196  cy_shift: 0
197 
198  tilting_lasers: {}
199 
200  checkerboards:
201  mmurooka_board:
202  spacing_x: 0.0
203  spacing_y: 0.0
204 """
205  if not os.path.exists(os.path.join(root_name, "config")):
206  os.mkdir(os.path.join(root_name, "config"))
207  file_path = os.path.join(root_name, "config", "free_cb_locations.yaml")
208  with open(file_path, "w") as f:
209  f.write(file_string)
210 
211 def generateFreeCameras(root_dir,
212  free_cameras_include_leg,
213  free_cameras_include_arm):
214  if free_cameras_include_leg and free_cameras_include_arm:
215  file_str = """
216  transforms:
217  LARM_chain_cb: [1, 1, 1, 1, 1, 1]
218  RARM_chain_cb: [1, 1, 1, 1, 1, 1]
219  LLEG_chain_cb: [1, 1, 1, 1, 1, 1]
220  RLEG_chain_cb: [1, 1, 1, 1, 1, 1]
221  CARMINE_joint: [1, 1, 1, 1, 1, 1]
222 
223  chains:
224  LARM_chain:
225  gearing: [0, 0, 0, 0, 0, 0]
226  RARM_chain:
227  gearing: [0, 0, 0, 0, 0, 0]
228  LLEG_chain:
229  gearing: [0, 0, 0, 0, 0, 0]
230  RLEG_chain:
231  gearing: [0, 0, 0, 0, 0, 0]
232  head_chain:
233  gearing: [0, 0]
234  torso_chain:
235  gearing: [0, 0]
236 
237  rectified_cams:
238  head_camera:
239  baseline_shift: 0
240  f_shift: 0
241  cx_shift: 0
242  cy_shift: 0
243 
244  tilting_lasers: {}
245 
246  checkerboards:
247  mmurooka_board:
248  spacing_x: 0
249  spacing_y: 0
250 
251 """
252  elif free_cameras_include_leg and not free_cameras_include_arm:
253  file_str = """
254  transforms:
255  LLEG_chain_cb: [1, 1, 1, 1, 1, 1]
256  RLEG_chain_cb: [1, 1, 1, 1, 1, 1]
257  CARMINE_joint: [1, 1, 1, 1, 1, 1]
258 
259  chains:
260  LARM_chain:
261  gearing: [0, 0, 0, 0, 0, 0]
262  RARM_chain:
263  gearing: [0, 0, 0, 0, 0, 0]
264  LLEG_chain:
265  gearing: [0, 0, 0, 0, 0, 0]
266  RLEG_chain:
267  gearing: [0, 0, 0, 0, 0, 0]
268  head_chain:
269  gearing: [0, 0]
270  torso_chain:
271  gearing: [0, 0]
272 
273  rectified_cams:
274  head_camera:
275  baseline_shift: 0
276  f_shift: 0
277  cx_shift: 0
278  cy_shift: 0
279 
280  tilting_lasers: {}
281 
282  checkerboards:
283  mmurooka_board:
284  spacing_x: 0
285  spacing_y: 0
286 
287 """
288  elif not free_cameras_include_leg and free_cameras_include_arm:
289  file_str = """
290  transforms:
291  LARM_chain_cb: [1, 1, 1, 1, 1, 1]
292  RARM_chain_cb: [1, 1, 1, 1, 1, 1]
293  CARMINE_joint: [1, 1, 1, 1, 1, 1]
294 
295  chains:
296  LARM_chain:
297  gearing: [0, 0, 0, 0, 0, 0]
298  RARM_chain:
299  gearing: [0, 0, 0, 0, 0, 0]
300  LLEG_chain:
301  gearing: [0, 0, 0, 0, 0, 0]
302  RLEG_chain:
303  gearing: [0, 0, 0, 0, 0, 0]
304  head_chain:
305  gearing: [0, 0]
306  torso_chain:
307  gearing: [0, 0]
308 
309  rectified_cams:
310  head_camera:
311  baseline_shift: 0
312  f_shift: 0
313  cx_shift: 0
314  cy_shift: 0
315 
316  tilting_lasers: {}
317 
318  checkerboards:
319  mmurooka_board:
320  spacing_x: 0
321  spacing_y: 0
322 
323 """
324  elif not free_cameras_include_leg and not free_cameras_include_arm:
325  file_str = """
326  transforms:
327  CARMINE_joint: [1, 1, 1, 1, 1, 1]
328 
329  chains:
330  LARM_chain:
331  gearing: [0, 0, 0, 0, 0, 0]
332  RARM_chain:
333  gearing: [0, 0, 0, 0, 0, 0]
334  LLEG_chain:
335  gearing: [0, 0, 0, 0, 0, 0]
336  RLEG_chain:
337  gearing: [0, 0, 0, 0, 0, 0]
338  head_chain:
339  gearing: [0, 0]
340  torso_chain:
341  gearing: [0, 0]
342 
343  rectified_cams:
344  head_camera:
345  baseline_shift: 0
346  f_shift: 0
347  cx_shift: 0
348  cy_shift: 0
349 
350  tilting_lasers: {}
351 
352  checkerboards:
353  mmurooka_board:
354  spacing_x: 0
355  spacing_y: 0
356 
357 """
358  file_path = os.path.join(root_dir, "config", "free_cameras.yaml")
359  with open(file_path, "w") as f:
360  f.write(file_str)
361 
362 def generateFreeArms(root_dir,
363  free_arms_use_arm,
364  free_arms_use_head,
365  free_arms_use_chest,
366  free_arms_use_leg):
367  file_str = """
368  transforms:
369  LARM_chain_cb: [1, 1, 1, 1, 1, 1]
370  RARM_chain_cb: [1, 1, 1, 1, 1, 1]
371  LLEG_chain_cb: [1, 1, 1, 1, 1, 1]
372  RLEG_chain_cb: [1, 1, 1, 1, 1, 1]
373  CARMINE_joint: [0, 0, 0, 1, 1, 1]
374 """
375  if free_arms_use_arm:
376  file_str = file_str + """
377  LARM_JOINT0: [ 0, 0, 0, 0.0, 1.0, 0.0 ]
378  LARM_JOINT1: [ 0, 0, 0, 1.0, 0.0, 0.0 ]
379  LARM_JOINT2: [ 0, 0, 0, 0.0, 0.0, 1.0 ]
380  LARM_JOINT3: [ 0, 0, 0, 0.0, 1.0, 0.0 ]
381  LARM_JOINT4: [ 0, 0, 0, 0.0, 0.0, 1.0 ]
382  LARM_JOINT5: [ 0, 0, 0, 1.0, 0.0, 0.0 ]
383  LARM_JOINT6: [ 0, 0, 0, 0.0, 1.0, 0.0 ]
384  RARM_JOINT0: [ 0, 0, 0, 0.0, 1.0, 0.0 ]
385  RARM_JOINT1: [ 0, 0, 0, 1.0, 0.0, 0.0 ]
386  RARM_JOINT2: [ 0, 0, 0, 0.0, 0.0, 1.0 ]
387  RARM_JOINT3: [ 0, 0, 0, 0.0, 1.0, 0.0 ]
388  RARM_JOINT4: [ 0, 0, 0, 0.0, 0.0, 1.0 ]
389  RARM_JOINT5: [ 0, 0, 0, 1.0, 0.0, 0.0 ]
390  RARM_JOINT6: [ 0, 0, 0, 0.0, 1.0, 0.0 ]
391 """
392  if free_arms_use_head:
393  file_str = file_str + """
394  HEAD_JOINT0: [ 0, 0, 0, 0.0, 0.0, 1.0 ]
395  HEAD_JOINT1: [ 0, 0, 0, 0.0, 1.0, 0.0 ]
396 
397 """
398  if free_arms_use_chest:
399  file_str = file_str + """
400  CHEST_JOINT0: [ 0, 0, 0, 0.0, 0.0, 1.0 ]
401  CHEST_JOINT1: [ 0, 0, 0, 0.0, 1.0, 0.0 ]
402 
403 """
404  if free_arms_use_leg:
405  file_str = file_str + """
406  LLEG_JOINT0: [0, 0, 0, 0.0, 0.0, 1.0]
407  LLEG_JOINT1: [0, 0, 0, 1.0, 0.0, 0.0]
408  LLEG_JOINT2: [0, 0, 0, 0.0, 1.0, 0.0]
409  LLEG_JOINT3: [0, 0, 0, 0.0, 1.0, 0.0]
410  LLEG_JOINT4: [0, 0, 0, 0.0, 1.0, 0.0]
411  LLEG_JOINT5: [0, 0, 0, 1.0, 0.0, 0.0]
412  LLEG_JOINT6: [0, 0, 0, 0.0, 0.0, 0.0]
413 """
414  file_str = file_str + """
415  chains:
416  LARM_chain:
417  gearing: [0, 0, 0, 0, 0, 0]
418  RARM_chain:
419  gearing: [0, 0, 0, 0, 0, 0]
420  LLEG_chain:
421  gearing: [0, 0, 0, 0, 0, 0]
422  RLEG_chain:
423  gearing: [0, 0, 0, 0, 0, 0]
424  head_chain:
425  gearing: [0, 0]
426  torso_chain:
427  gearing: [0, 0]
428 
429  rectified_cams:
430  head_camera:
431  baseline_shift: 0
432  f_shift: 0
433  cx_shift: 0
434  cy_shift: 0
435 
436  tilting_lasers: {}
437 
438  checkerboards:
439  mmurooka_board:
440  spacing_x: 0
441  spacing_y: 0
442 """
443  file_path = os.path.join(root_dir, "config", "free_arms.yaml")
444  with open(file_path, "w") as f:
445  f.write(file_str)
446 def generateSystemYaml(root_dir):
447  file_str = """
448 base_link: BODY
449 
450 sensors:
451 
452  chains:
453  LARM_chain:
454  root: CHEST_LINK1
455  tip: LARM_cb_jig
456  cov:
457  joint_angles: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01]
458  gearing: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
459  RARM_chain:
460  root: CHEST_LINK1
461  tip: RARM_cb_jig
462  cov:
463  joint_angles: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01]
464  gearing: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
465  head_chain:
466  root: CHEST_LINK1
467  tip: HEAD_LINK1
468  cov:
469  joint_angles: [0.01, 0.01]
470  gearing: [1.0, 1.0]
471  torso_chain:
472  root: BODY
473  tip: CHEST_LINK1
474  cov:
475  joint_angles: [0.01, 0.01]
476  gearing: [1.0, 1.0]
477  LLEG_chain:
478  root: BODY
479  tip: lleg_end_coords # LLEG_LINK5?
480  cov:
481  joint_angles: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01]
482  gearing: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
483  RLEG_chain:
484  root: BODY
485  tip: rleg_end_coords # RLEG_LINK5?
486  cov:
487  joint_angles: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01]
488  gearing: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
489  rectified_cams:
490  head_camera:
491  chain_id: head_chain #TODO: get rid of this
492  frame_id: camera_rgb_optical_frame
493 # frame_id: HEAD_LINK1
494  baseline_shift: 0.0
495 # baseline_rgbd: 0.075 ## comment out if we run all_pipelines.launch with use_kinect
496  f_shift: 0.0
497  cx_shift: 0.0
498  cy_shift: 0.0
499  cov: {u: 0.25, v: 0.25, x: 0.25}
500 
501  tilting_lasers: {}
502 
503 checkerboards:
504  mmurooka_board:
505  corners_x: 5
506  corners_y: 6
507  spacing_x: 0.03
508  spacing_y: 0.03
509 
510 transforms:
511  LARM_chain_cb: [-0.1, 0, 0, 0, 0, 0]
512  RARM_chain_cb: [0, 0, 0, 0, 0, 0]
513 #default_floating_initial_pose: [0.3, 0, 0.2, -1.2092, 1.2092, -1.2092]
514 #default_floating_initial_pose: [0, 0, 0, 0, 0, 0]
515 initial_poses: "/tmp/staro_calibration/config_0_poses.yaml"
516 # xyz: [-0.002956968077825933, 0.16898467170866147, -0.20050853695600393]
517 # rpy: (-0.04425102767135782, 0.01876497698337332, -0.019873022766080706)
518 """
519  with open(os.path.join(root_dir, "config", "system.yaml"), "w") as f:
520  f.write(file_str)
521 
522 def generateSh(root_dir):
523  global counter
524  port = counter + 11311
525  counter = counter + 1
526  file_str = """
527 #! /bin/bash
528 set +x
529 rosparam delete /calibration_config
530 cd ${root_dir}
531 if [ -f robot_calibrated.xml ]; then
532  echo "robot_calibrated.xml already exists. Either back up this file or remove it before continuing"
533  exit 1
534 fi
535 
536 echo "Checking if we can write to robot_calibrated.xml..."
537 touch robot_calibrated.xml
538 if [ "$?" -ne "0" ]; then
539  echo "Not able to write to robot_calibrated.xml"
540  echo "Make sure you run this script from a directory that for which you have write permissions."
541  exit 1
542 fi
543 rm robot_calibrated.xml
544 echo "Success"
545 
546 # staro_calibration
547 roslaunch estimation_config.launch
548 rosrun calibration_estimation multi_step_cov_estimator.py staro_calibration/cal_measurements.bag /tmp/staro_calibration __name:=cal_cov_estimator
549 
550 est_return_val=$?
551 
552 if [ "$est_return_val" -ne "0" ]; then
553  echo "Estimator exited prematurely with error code [$est_return_val]"
554  exit 1
555 fi
556 
557 # Make all the temporary files writable
558 chmod ag+w staro_calibration/*
559 """
560  replaced_str = replaceStringWithDict(file_str, {"root_dir": root_dir, "port": port})
561  with open(os.path.join(root_dir, "calibrate_staro.sh"), "w") as f:
562  f.write(replaced_str)
563  os.chmod(os.path.join(root_dir, "calibrate_staro.sh"), 0o0755)
564 
565 def copyBagFiles(root_dir):
566  os.mkdir(os.path.join(root_dir, "staro_calibration"))
567  to_path = os.path.join(root_dir, "staro_calibration", "cal_measurements.bag")
568  shutil.copyfile("cal_measurements.bag", to_path)
569 
570 def genFiles(estimation_config_include_leg,
571  estimation_config_use_chain,
572  estimation_config_calibrate_joint,
573  free_cb_locations_use_leg,
574  free_cameras_include_leg,
575  free_cameras_include_arm,
576  free_arms_use_arm,
577  free_arms_use_head,
578  free_arms_use_chest,
579  free_arms_use_leg):
580  directory_name = "test_%s_%s_%s_%s_%s_%s_%s_%s_%s_%s" % (estimation_config_include_leg,
581  estimation_config_use_chain,
582  estimation_config_calibrate_joint,
583  free_cb_locations_use_leg,
584  free_cameras_include_leg,
585  free_cameras_include_arm,
586  free_arms_use_arm,
587  free_arms_use_head,
588  free_arms_use_chest,
589  free_arms_use_leg)
590  if "--cleanup" in sys.argv:
591  if os.path.exists(directory_name):
592  shutil.rmtree(directory_name)
593  os.mkdir(directory_name)
594  generateEstimationConfig(directory_name,
595  estimation_config_include_leg,
596  estimation_config_use_chain,
597  estimation_config_calibrate_joint)
598  generateFreeCBLocations(directory_name, free_cb_locations_use_leg)
599  generateFreeCameras(directory_name, free_cameras_include_leg,
600  free_cameras_include_arm)
601  generateFreeArms(directory_name,
602  free_arms_use_arm,
603  free_arms_use_head,
604  free_arms_use_chest,
605  free_arms_use_leg)
606  generateSystemYaml(directory_name)
607  generateSh(directory_name)
608  copyBagFiles(directory_name)
609 
610 
612  parallel_num = 32
613  # find all calibrate_staro.sh
614  sh_files = []
615  free_workers = [None] * parallel_num
616  for root, dirs, files in os.walk('.'):
617  if "calibrate_staro.sh" in files and "latest_calibrated_xml" not in files:
618  sh_files.append(os.path.join(root, "calibrate_staro.sh"))
619  del dirs[:]
620  while len(sh_files) > 0:
621  for p, i in zip(free_workers, range(len(free_workers))):
622  if p == None or p.poll() != None:
623  # we can use the worker
624  new_env = os.environ.copy()
625  new_env["ROS_MASTER_URI"] = "http://localhost:%d" % (11311 + i + 1)
626  process = subprocess.Popen([sh_files.pop()], env=new_env, shell=True)
627  free_workers[i] = process
628  print("%d tasks are remained" % (len(sh_files)))
629  print(free_workers)
630  time.sleep(1)
631 
632 
633 
634 def main():
635  if "--execute" in sys.argv:
637  return
638  for estimation_config_include_leg in (False, True):
639  for estimation_config_use_chain in (False, True):
640  for estimation_config_calibrate_joint in (False, True):
641  for free_cb_locations_use_leg in (False, True):
642  for free_cameras_include_leg in (False, True):
643  for free_cameras_include_arm in (False, True):
644  for free_arms_use_arm in (False, True):
645  for free_arms_use_head in (False, True):
646  for free_arms_use_chest in (False, True):
647  for free_arms_use_leg in (False, True):
648  genFiles(estimation_config_include_leg,
649  estimation_config_use_chain,
650  estimation_config_calibrate_joint,
651  free_cb_locations_use_leg,
652  free_cameras_include_leg,
653  free_cameras_include_arm,
654  free_arms_use_arm,
655  free_arms_use_head,
656  free_arms_use_chest,
657  free_arms_use_leg)
658 
659 if __name__ == "__main__":
660  main()
def generateFreeArms(root_dir, free_arms_use_arm, free_arms_use_head, free_arms_use_chest, free_arms_use_leg)
def generateEstimationConfig(root_dir, estimation_config_include_leg, estimation_config_use_chain, estimation_config_calibrate_joint)
def generateFreeCameras(root_dir, free_cameras_include_leg, free_cameras_include_arm)
def replaceStringWithDict(format, variables)
def genFiles(estimation_config_include_leg, estimation_config_use_chain, estimation_config_calibrate_joint, free_cb_locations_use_leg, free_cameras_include_leg, free_cameras_include_arm, free_arms_use_arm, free_arms_use_head, free_arms_use_chest, free_arms_use_leg)
def generateFreeCBLocations(root_name, free_cb_locations_use_leg)


jsk_calibration
Author(s):
autogenerated on Fri May 14 2021 02:51:46