port_samples.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 
3 # This script is used to convert PR2 Samples into PR2 Lite Samples
4 # Author Vijay Pradeep
5 # Modified 11/11 by Adam Leeper
6 
7 import roslib; roslib.load_manifest('pr2_calibration_launch')
8 import rospy
9 import yaml
10 import sys
11 import os
12 
13 input_dir = rospy.myargv()[1]
14 output_dir = rospy.myargv()[2]
15 sample_names = [x for x in os.listdir(input_dir) if ".yaml" in x]
16 sample_names.sort()
17 full_input_paths = [input_dir + "/" + x for x in sample_names]
18 full_output_paths = [output_dir + "/" + x for x in sample_names]
19 
20 #TODO Add support for left OR right arm
21 
22 for cur_input_path, cur_output_path in zip(full_input_paths, full_output_paths):
23  print("On sample [%s]" % cur_input_path)
24  cur_config = yaml.load(open(cur_input_path))
25 
26  # Don't use any of the l_forearm samples
27  if 'forearm_left_rect' not in [ x['cam_id'] for x in cur_config['camera_measurements']]:
28  next_config = {}
29  if 'forearm_right_rect' in [ x['cam_id'] for x in cur_config['camera_measurements']]:
30  next_config['camera_measurements'] = [{'cam_id':'forearm_right_rect', 'config':'small_cb_4x5'}]
31  else:
32  next_config['camera_measurements'] = [{'cam_id':'kinect_rect', 'config':'small_cb_4x5'}, {'cam_id':'prosilica_rect', 'config':'small_cb_4x5'} ]
33  next_config['joint_commands'] = [x for x in cur_config['joint_commands'] if x['controller'] in ['head_traj_controller', 'r_arm_controller']]
34  next_config['joint_measurements'] = [x for x in cur_config['joint_measurements'] if x['chain_id'] in ['head_chain', 'right_arm_chain']]
35  if 'tilt_laser' in [ x['laser_id'] for x in cur_config['laser_measurements']]:
36  next_config['laser_measurements'] = [{'config': 'small_cb_4x5', 'laser_id': 'tilt_laser'}]
37  else:
38  next_config['laser_measurements'] = []
39  next_config['sample_id'] = cur_config['sample_id']
40  next_config['target'] = cur_config['target']
41 
42  # Tilt the head down by about 11 degrees to account for higher kinect position.
43  # Yes, this is a total hack.
44  for head_cmd in [x for x in next_config['joint_commands'] if x['controller'] == 'head_traj_controller']:
45  for cur_segment in head_cmd['segments']:
46  cur_segment['positions'][1] = cur_segment['positions'][1] + 0.2
47 
48  outfile = file(cur_output_path, 'w')
49  yaml.dump(next_config, outfile)
50  outfile.close()
51  else:
52  print("Skipping")
53 
54 


pr2_se_calibration_launch
Author(s): Adam Leeper, Vijay Pradeep
autogenerated on Tue Jun 1 2021 02:51:02