gear.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (Apache License)
4 #
5 # Copyright 2016 Open Source Robotics Foundation
6 #
7 # Licensed under the Apache License, Version 2.0 (the "License");
8 # you may not use this file except in compliance with the License.
9 # You may obtain a copy of the License at
10 #
11 # http://www.apache.org/licenses/LICENSE-2.0
12 #
13 # Unless required by applicable law or agreed to in writing, software
14 # distributed under the License is distributed on an "AS IS" BASIS,
15 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16 # See the License for the specific language governing permissions and
17 # limitations under the License.
18 
19 from __future__ import print_function
20 
21 import argparse
22 import em
23 import math
24 import os
25 import subprocess
26 import sys
27 import yaml
28 
29 this_dir = os.path.abspath(os.path.dirname(__file__))
30 template_files = [
31  os.path.join(this_dir, '..', '..', 'share', 'osrf_gear', 'worlds', 'gear.world.template'),
32  os.path.join(this_dir, '..', '..', 'share', 'osrf_gear', 'launch', 'gear.launch.template'),
33  os.path.join(this_dir, '..', '..', 'share', 'osrf_gear', 'launch', 'gear.urdf.xacro.template'),
34 ]
35 arm_configs = {
36  'ur10': {
37  'default_initial_joint_states': {
38  'linear_arm_actuator_joint': 0,
39  'shoulder_pan_joint': 0,
40  'shoulder_lift_joint': -1.13,
41  'elbow_joint': 1.51,
42  'wrist_1_joint': 3.77,
43  'wrist_2_joint': -1.51,
44  'wrist_3_joint': 0,
45  }
46  },
47 }
48 sensor_configs = {
49  'break_beam': None,
50  'proximity_sensor': None,
51  'logical_camera': None,
52  'laser_profiler': None,
53 }
54 default_bin_origins = {
55  'bin1': [-1.0, -1.33, 0],
56  'bin2': [-1.0, -0.535, 0],
57  'bin3': [-1.0, 0.23, 0],
58  'bin4': [-1.0, 0.995, 0],
59  'bin5': [-0.3, -1.33, 0],
60  'bin6': [-0.3, -0.535, 0],
61  'bin7': [-0.3, 0.23, 0],
62  'bin8': [-0.3, 0.995, 0],
63 }
64 configurable_options = {
65  'insert_models_over_bins': False,
66  'disable_shadows': False,
67  'fill_demo_tray': False,
68  'spawn_extra_models': False,
69  'model_type_aliases': {
70  'belt_model_type1': 'part1',
71  'belt_model_type2': 'part2',
72  },
73 }
74 
75 
76 def prepare_arguments(parser):
77  add = parser.add_argument
78  add('-n', '--dry-run', action='store_true', default=False,
79  help='print generated files to stdout, but do not write them to disk')
80  add('-o', '--output', default=os.getcwd(),
81  help='directory in which to output the generated files')
82  mex_group = parser.add_mutually_exclusive_group(required=False)
83  add = mex_group.add_argument
84  add('config', nargs="?", metavar="CONFIG",
85  help='yaml string that is the configuration')
86  add('-f', '--file', nargs='+', help='list of paths to yaml files that contain the '
87  'configuration (contents will be concatenated)')
88 
89 
90 eval_local_vars = {n: getattr(math, n) for n in dir(math) if not n.startswith('__')}
91 
92 
93 def expand_to_float(val):
94  if isinstance(val, str):
95  return float(eval(val, {}, eval_local_vars))
96  return float(val)
97 
98 
100  for k, v in yaml_dict.items():
101  if isinstance(v, dict):
102  yaml_dict[k] = expand_yaml_substitutions(v)
103  if k in ['xyz', 'rpy']:
104  yaml_dict[k] = [expand_to_float(x) for x in v]
105  if k in ['initial_joint_states']:
106  yaml_dict[k] = {kp: expand_to_float(vp) for kp, vp in v.items()}
107  return yaml_dict
108 
109 
110 class ArmInfo:
111  def __init__(self, arm_type, initial_joint_states):
112  self.type = arm_type
113  self.initial_joint_states = initial_joint_states
114 
115 
116 class ModelInfo:
117  def __init__(self, model_type, pose, reference_frame):
118  self.type = model_type
119  self.pose = pose
120  self.reference_frame = reference_frame
121 
123  def __init__(self, name, sensor_type, pose):
124  self.name = name
125  self.type = sensor_type
126  self.pose = pose
127 
128 
129 class PoseInfo:
130  def __init__(self, xyz, rpy):
131  self.xyz = [str(f) for f in xyz]
132  self.rpy = [str(f) for f in rpy]
133 
134 
136  def __init__(self, drop_region_min, drop_region_max):
137  self.min = [str(f) for f in drop_region_min]
138  self.max = [str(f) for f in drop_region_max]
139 
140 
142  def __init__(self, model_type, destination):
143  self.type = model_type
144  self.destination = destination
145 
146 
147 def get_field_with_default(data_dict, entry, default_value):
148  if entry in data_dict:
149  return data_dict[entry]
150  else:
151  return default_value
152 
153 
154 def get_required_field(entry_name, data_dict, required_entry):
155  if required_entry not in data_dict:
156  print("Error: '{0}' entry does not contain a required '{1}' entry"
157  .format(entry_name, required_entry),
158  file=sys.stderr)
159  sys.exit(1)
160  return data_dict[required_entry]
161 
162 
163 def replace_type_aliases(model_type):
164  if model_type in configurable_options['model_type_aliases']:
165  model_type = configurable_options['model_type_aliases'][model_type]
166  return model_type
167 
168 
169 def create_arm_info(arm_dict):
170  arm_type = get_required_field('arm', arm_dict, 'type')
171  if arm_type not in arm_configs:
172  print("Error: arm type '{0}' is not one of the valid arm entries: {1}"
173  .format(arm_type, arm_configs), file=sys.stderr)
174  sys.exit(1)
175  default_joint_states = arm_configs[arm_type]['default_initial_joint_states']
176  merged_initial_joint_states = dict(default_joint_states)
177  if 'initial_joint_states' in arm_dict:
178  initial_joint_states = arm_dict['initial_joint_states']
179  for k, v in initial_joint_states.items():
180  if k not in merged_initial_joint_states:
181  print("Error: given joint name '{0}' is not one of the known joint "
182  "states for the '{1}' type arm: {2}".format(k, arm_type, default_joint_states),
183  file=sys.stderr)
184  sys.exit(1)
185  merged_initial_joint_states[k] = v
186  return ArmInfo(arm_type, merged_initial_joint_states)
187 
188 
189 def create_pose_info(pose_dict):
190  xyz = get_field_with_default(pose_dict, 'xyz', [0, 0, 0])
191  rpy = get_field_with_default(pose_dict, 'rpy', [0, 0, 0])
192  for key in pose_dict:
193  if key not in ['xyz', 'rpy']:
194  print("Warning: ignoring unknown entry in 'pose': " + key, file=sys.stderr)
195  return PoseInfo(xyz, rpy)
196 
197 
198 def create_sensor_info(name, sensor_data):
199  sensor_type = get_required_field(name, sensor_data, 'type')
200  pose_dict = get_required_field(name, sensor_data, 'pose')
201  for key in sensor_data:
202  if key not in ['type', 'pose']:
203  print("Warning: ignoring unknown entry in '{0}': {1}"
204  .format(name, key), file=sys.stderr)
205  if sensor_type not in sensor_configs:
206  print("Error: given sensor type '{0}' is not one of the known sensor types: {1}"
207  .format(sensor_type, sensor_configs.keys()), file=sys.stderr)
208  pose_info = create_pose_info(pose_dict)
209  return SensorInfo(name, sensor_type, pose_info)
210 
211 
212 def create_sensor_infos(sensors_dict):
213  sensor_infos = {}
214  for name, sensor_data in sensors_dict.items():
215  sensor_infos[name] = create_sensor_info(name, sensor_data)
216  return sensor_infos
217 
218 
219 def create_model_info(model_name, model_data):
220  model_type = get_required_field(model_name, model_data, 'type')
221  model_type = replace_type_aliases(model_type)
222  pose_dict = get_required_field(model_name, model_data, 'pose')
223  reference_frame = get_field_with_default(model_data, 'reference_frame', '')
224  for key in model_data:
225  if key not in ['type', 'pose', 'reference_frame']:
226  print("Warning: ignoring unknown entry in '{0}': {1}"
227  .format(model_name, key), file=sys.stderr)
228  pose_info = create_pose_info(pose_dict)
229  return ModelInfo(model_type, pose_info, reference_frame)
230 
231 
232 def create_models_to_spawn_infos(models_to_spawn_dict):
233  models_to_spawn_infos = {}
234  for reference_frame, reference_frame_data in models_to_spawn_dict.items():
235  models = get_required_field(reference_frame, reference_frame_data, 'models')
236  model_count = 0
237  for model_name, model_to_spawn_data in models.items():
238  model_to_spawn_data['reference_frame'] = reference_frame
239  model_info = create_model_info(model_name, model_to_spawn_data)
240  # assign each model a unique name because gazebo can't do this
241  # if the models all spawn at the same time
242  scoped_model_name = reference_frame.replace('::', '|') + '|' + \
243  model_info.type + '_' + str(model_count)
244  models_to_spawn_infos[scoped_model_name] = model_info
245  model_count += 1
246  return models_to_spawn_infos
247 
248 
249 def create_models_over_bins_infos(models_over_bins_dict):
250  models_to_spawn_infos = {}
251  bin_width = 0.6
252  bin_height = 0.75
253  for bin_name, bin_dict in models_over_bins_dict.items():
254  if bin_name in default_bin_origins:
255  offset_xyz = [
256  default_bin_origins[bin_name][0] - bin_width / 2,
257  default_bin_origins[bin_name][1] - bin_width / 2,
258  bin_height]
259  # Allow the origin of the bin to be over-written
260  if 'xyz' in bin_dict:
261  offset_xyz = bin_dict['xyz']
262  else:
263  offset_xyz = get_required_field(bin_name, bin_dict, 'xyz')
264 
265  models = get_required_field(bin_name, bin_dict, 'models') or {}
266  for model_type, model_to_spawn_dict in models.items():
267  model_count = 0
268  model_to_spawn_data = {}
269  model_to_spawn_data['type'] = model_type
270  model_to_spawn_data['reference_frame'] = 'world'
271  xyz_start = get_required_field(
272  model_type, model_to_spawn_dict, 'xyz_start')
273  xyz_end = get_required_field(
274  model_type, model_to_spawn_dict, 'xyz_end')
275  rpy = get_required_field(model_type, model_to_spawn_dict, 'rpy')
276  num_models_x = get_required_field(
277  model_type, model_to_spawn_dict, 'num_models_x')
278  num_models_y = get_required_field(
279  model_type, model_to_spawn_dict, 'num_models_y')
280  step_size = [
281  (xyz_end[0] - xyz_start[0]) / max(1, num_models_x - 1),
282  (xyz_end[1] - xyz_start[1]) / max(1, num_models_y - 1)]
283 
284  # Create a grid of models
285  for idx_x in range(num_models_x):
286  for idx_y in range(num_models_y):
287  xyz = [
288  offset_xyz[0] + xyz_start[0] + idx_x * step_size[0],
289  offset_xyz[1] + xyz_start[1] + idx_y * step_size[1],
290  offset_xyz[2] + xyz_start[2]]
291  model_to_spawn_data['pose'] = {'xyz': xyz, 'rpy': rpy}
292  model_info = create_model_info(model_type, model_to_spawn_data)
293  # assign each model a unique name because gazebo can't do this
294  # if the models all spawn at the same time
295  scoped_model_name = bin_name + '|' + \
296  model_info.type + '_' + str(model_count)
297  models_to_spawn_infos[scoped_model_name] = model_info
298  model_count += 1
299  return models_to_spawn_infos
300 
301 
302 def create_belt_part_infos(belt_parts_dict):
303  belt_part_infos = {}
304  for spawn_time, belt_part_dict in belt_parts_dict.items():
305  belt_part_infos[spawn_time] = create_model_info('belt_part', belt_part_dict)
306  return belt_part_infos
307 
308 
309 def create_drops_info(drops_dict):
310  drops_info = {}
311  drop_region = get_required_field('drops', drops_dict, 'drop_region')
312  drop_region_min = get_required_field('drop_region', drop_region, 'min')
313  drop_region_min_xyz = get_required_field('min', drop_region_min, 'xyz')
314  drop_region_max = get_required_field('drop_region', drop_region, 'max')
315  drop_region_max_xyz = get_required_field('max', drop_region_max, 'xyz')
316 
317  drops_info['drop_region'] = DropRegionInfo(drop_region_min_xyz, drop_region_max_xyz)
318 
319  drops_dict = get_required_field('drops', drops_dict, 'dropped_parts')
320  dropped_part_infos = {}
321  for drop_name, dropped_part_dict in drops_dict.items():
322  part_type = get_required_field(drop_name, dropped_part_dict, 'part_type_to_drop')
323  part_type = replace_type_aliases(part_type)
324  destination_info = get_required_field(drop_name, dropped_part_dict, 'destination')
325  destination = create_pose_info(destination_info)
326  dropped_part_infos[drop_name] = DroppedPartInfo(part_type, destination)
327  drops_info['dropped_parts'] = dropped_part_infos
328  print(drops_info)
329  return drops_info
330 
331 
332 def create_order_info(name, order_dict):
333  announcement_time = get_required_field(name, order_dict, 'announcement_time')
334  parts_dict = get_required_field(name, order_dict, 'parts')
335  parts = []
336  for part_name, part_dict in parts_dict.items():
337  parts.append(create_model_info(part_name, part_dict))
338  return {'announcement_time': announcement_time, 'parts': parts}
339 
340 
341 def create_order_infos(orders_dict):
342  order_infos = {}
343  for order_name, order_dict in orders_dict.items():
344  order_infos[order_name] = create_order_info(order_name, order_dict)
345  return order_infos
346 
347 
349  bin_infos = {}
350  for bin_name, xyz in default_bin_origins.items():
351  bin_infos[bin_name] = PoseInfo(xyz, [0, 0, 1.5708])
352  return bin_infos
353 
354 
355 def create_options_info(options_dict):
356  options = configurable_options
357  for option, val in options_dict.items():
358  options[option] = val
359  return options
360 
361 
362 def prepare_template_data(config_dict):
363  template_data = {
364  'arm': None,
365  'sensors': {},
366  'models_to_insert': {},
367  'models_to_spawn': {},
368  'belt_parts': {},
369  'drops': {},
370  'orders': {},
371  'options': {},
372  }
373  # Process the options first as they may affect the processing of the rest
374  options_dict = get_field_with_default(config_dict, 'options', {})
375  template_data['options'].update(create_options_info(options_dict))
376 
377  for key, value in config_dict.items():
378  if key == 'arm':
379  template_data['arm'] = create_arm_info(value)
380  elif key == 'sensors':
381  template_data['sensors'].update(
382  create_sensor_infos(value))
383  elif key == 'models_over_bins':
384  template_data['models_to_insert'].update(
386  elif key == 'belt_parts':
387  template_data['belt_parts'].update(create_belt_part_infos(value))
388  elif key == 'drops':
389  template_data['drops'].update(create_drops_info(value))
390  elif key == 'orders':
391  template_data['orders'].update(create_order_infos(value))
392  elif key == 'options':
393  pass
394  elif key == 'models_to_spawn':
395  template_data['models_to_spawn'].update(
397  else:
398  print("Error: unknown top level entry '{0}'".format(key), file=sys.stderr)
399  sys.exit(1)
400  template_data['bins'] = create_bin_infos()
401  return template_data
402 
403 
404 def generate_files(template_data):
405  files = {}
406  for template_file in template_files:
407  with open(template_file, 'r') as f:
408  data = f.read()
409  files[template_file] = em.expand(data, template_data)
410  return files
411 
412 
413 def main(sysargv=None):
414  parser = argparse.ArgumentParser(
415  description='Prepares and then executes a gazebo simulation based on configurations.')
416  prepare_arguments(parser)
417  args = parser.parse_args(sysargv)
418  config_data = args.config or ''
419  if args.file is not None:
420  for file in args.file:
421  with open(file, 'r') as f:
422  comp_config_data = f.read()
423  config_data += comp_config_data
424  dict_config = yaml.load(config_data) or {}
425  expanded_dict_config = expand_yaml_substitutions(dict_config)
426  print(yaml.dump({'Using configuration': expanded_dict_config}))
427  template_data = prepare_template_data(expanded_dict_config)
428  files = generate_files(template_data)
429  if not args.dry_run and not os.path.isdir(args.output):
430  if os.path.exists(args.output) and not os.path.isdir(args.output):
431  print("Error, given output directory exists but is not a directory.", file=sys.stderr)
432  sys.exit(1)
433  print('creating directory: ' + args.output)
434  os.makedirs(args.output)
435  for name, content in files.items():
436  if name.endswith('.template'):
437  name = name[:-len('.template')]
438  name = os.path.basename(name)
439  if args.dry_run:
440  print('# file: ' + name)
441  print(content)
442  else:
443  file_path = os.path.join(args.output, name)
444  print('writing file ' + file_path)
445  with open(file_path, 'w+') as f:
446  f.write(content)
447  cmd = [
448  'roslaunch',
449  os.path.join(args.output, 'gear.launch'),
450  'world_path:=' + os.path.join(args.output, 'gear.world'),
451  'gear_urdf_xacro:=' + os.path.join(args.output, 'gear.urdf.xacro'),
452  ]
453  print("Running command: " + ' '.join(cmd))
454  if not args.dry_run:
455  try:
456  p = subprocess.Popen(cmd)
457  p.wait()
458  except KeyboardInterrupt:
459  pass
460  finally:
461  p.wait()
462  return p.returncode
463 
464 if __name__ == '__main__':
465  sys.exit(main())
def get_field_with_default(data_dict, entry, default_value)
Definition: gear.py:147
initial_joint_states
Definition: gear.py:113
def main(sysargv=None)
Definition: gear.py:413
def create_models_over_bins_infos(models_over_bins_dict)
Definition: gear.py:249
def create_belt_part_infos(belt_parts_dict)
Definition: gear.py:302
def __init__(self, model_type, pose, reference_frame)
Definition: gear.py:117
def expand_yaml_substitutions(yaml_dict)
Definition: gear.py:99
def create_order_info(name, order_dict)
Definition: gear.py:332
def create_drops_info(drops_dict)
Definition: gear.py:309
def get_required_field(entry_name, data_dict, required_entry)
Definition: gear.py:154
def replace_type_aliases(model_type)
Definition: gear.py:163
def __init__(self, arm_type, initial_joint_states)
Definition: gear.py:111
def create_options_info(options_dict)
Definition: gear.py:355
def __init__(self, name, sensor_type, pose)
Definition: gear.py:123
def prepare_arguments(parser)
Definition: gear.py:76
def prepare_template_data(config_dict)
Definition: gear.py:362
def create_order_infos(orders_dict)
Definition: gear.py:341
def create_models_to_spawn_infos(models_to_spawn_dict)
Definition: gear.py:232
def generate_files(template_data)
Definition: gear.py:404
def create_bin_infos()
Definition: gear.py:348
def create_pose_info(pose_dict)
Definition: gear.py:189
def create_arm_info(arm_dict)
Definition: gear.py:169
def create_model_info(model_name, model_data)
Definition: gear.py:219
def create_sensor_info(name, sensor_data)
Definition: gear.py:198
def expand_to_float(val)
Definition: gear.py:93
def __init__(self, drop_region_min, drop_region_max)
Definition: gear.py:136
def create_sensor_infos(sensors_dict)
Definition: gear.py:212
def __init__(self, model_type, destination)
Definition: gear.py:142
def __init__(self, xyz, rpy)
Definition: gear.py:130


osrf_gear
Author(s):
autogenerated on Wed Sep 7 2016 03:48:12