19 from __future__ 
import print_function
    29 this_dir = os.path.abspath(os.path.dirname(__file__))
    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'),
    37         'default_initial_joint_states': {
    38             'linear_arm_actuator_joint': 0,
    39             'shoulder_pan_joint': 0,
    40             'shoulder_lift_joint': -1.13,
    42             'wrist_1_joint': 3.77,
    43             'wrist_2_joint': -1.51,
    50     'proximity_sensor': 
None,
    51     'logical_camera': 
None,
    52     'laser_profiler': 
None,
    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],
    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',
    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)')
    90 eval_local_vars = {n: getattr(math, n) 
for n 
in dir(math) 
if not n.startswith(
'__')}
    94     if isinstance(val, str):
    95         return float(eval(val, {}, eval_local_vars))
   100     for k, v 
in yaml_dict.items():
   101         if isinstance(v, dict):
   103         if k 
in [
'xyz', 
'rpy']:
   105         if k 
in [
'initial_joint_states']:
   111     def __init__(self, arm_type, initial_joint_states):
   117     def __init__(self, model_type, pose, reference_frame):
   131         self.
xyz = [str(f) 
for f 
in xyz]
   132         self.
rpy = [str(f) 
for f 
in rpy]
   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]
   148     if entry 
in data_dict:
   149         return data_dict[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),
   160     return data_dict[required_entry]
   164     if model_type 
in configurable_options[
'model_type_aliases']:
   165         model_type = configurable_options[
'model_type_aliases'][model_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)
   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),
   185             merged_initial_joint_states[k] = v
   186     return ArmInfo(arm_type, merged_initial_joint_states)
   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)
   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)
   209     return SensorInfo(name, sensor_type, pose_info)
   214     for name, sensor_data 
in sensors_dict.items():
   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)
   229     return ModelInfo(model_type, pose_info, reference_frame)
   233     models_to_spawn_infos = {}
   234     for reference_frame, reference_frame_data 
in models_to_spawn_dict.items():
   237         for model_name, model_to_spawn_data 
in models.items():
   238             model_to_spawn_data[
'reference_frame'] = reference_frame
   242             scoped_model_name = reference_frame.replace(
'::', 
'|') + 
'|' + \
   243               model_info.type + 
'_' + str(model_count)
   244             models_to_spawn_infos[scoped_model_name] = model_info
   246     return models_to_spawn_infos
   250     models_to_spawn_infos = {}
   253     for bin_name, bin_dict 
in models_over_bins_dict.items():
   254         if bin_name 
in default_bin_origins:
   256                 default_bin_origins[bin_name][0] - bin_width / 2,
   257                 default_bin_origins[bin_name][1] - bin_width / 2,
   260             if 'xyz' in bin_dict:
   261                 offset_xyz = bin_dict[
'xyz']
   266         for model_type, model_to_spawn_dict 
in models.items():
   268             model_to_spawn_data = {}
   269             model_to_spawn_data[
'type'] = model_type
   270             model_to_spawn_data[
'reference_frame'] = 
'world'   272                 model_type, model_to_spawn_dict, 
'xyz_start')
   274                 model_type, model_to_spawn_dict, 
'xyz_end')
   277                 model_type, model_to_spawn_dict, 
'num_models_x')
   279                 model_type, model_to_spawn_dict, 
'num_models_y')
   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)]
   285             for idx_x 
in range(num_models_x):
   286                 for idx_y 
in range(num_models_y):
   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}
   295                     scoped_model_name = bin_name + 
'|' + \
   296                         model_info.type + 
'_' + str(model_count)
   297                     models_to_spawn_infos[scoped_model_name] = model_info
   299     return models_to_spawn_infos
   304     for spawn_time, belt_part_dict 
in belt_parts_dict.items():
   306     return belt_part_infos
   317     drops_info[
'drop_region'] = 
DropRegionInfo(drop_region_min_xyz, drop_region_max_xyz)
   320     dropped_part_infos = {}
   321     for drop_name, dropped_part_dict 
in drops_dict.items():
   326         dropped_part_infos[drop_name] = 
DroppedPartInfo(part_type, destination)
   327     drops_info[
'dropped_parts'] = dropped_part_infos
   336     for part_name, part_dict 
in parts_dict.items():
   338     return {
'announcement_time': announcement_time, 
'parts': parts}
   343     for order_name, order_dict 
in orders_dict.items():
   350     for bin_name, xyz 
in default_bin_origins.items():
   351         bin_infos[bin_name] = 
PoseInfo(xyz, [0, 0, 1.5708])
   356     options = configurable_options
   357     for option, val 
in options_dict.items():
   358         options[option] = val
   366         'models_to_insert': {},
   367         'models_to_spawn': {},
   377     for key, value 
in config_dict.items():
   380         elif key == 
'sensors':
   381             template_data[
'sensors'].update(
   383         elif key == 
'models_over_bins':
   384             template_data[
'models_to_insert'].update(
   386         elif key == 
'belt_parts':
   390         elif key == 
'orders':
   392         elif key == 
'options':
   394         elif key == 
'models_to_spawn':
   395             template_data[
'models_to_spawn'].update(
   398             print(
"Error: unknown top level entry '{0}'".format(key), file=sys.stderr)
   406     for template_file 
in template_files:
   407         with open(template_file, 
'r') as f:   409         files[template_file] = em.expand(data, template_data)   414     parser = argparse.ArgumentParser(
   415         description=
'Prepares and then executes a gazebo simulation based on configurations.')
   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 {}
   426     print(yaml.dump({
'Using configuration': expanded_dict_config}))
   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)
   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)
   440             print(
'# file: ' + name)
   443             file_path = os.path.join(args.output, name)
   444             print(
'writing file ' + file_path)
   445             with open(file_path, 
'w+') 
as f:
   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'),
   453     print(
"Running command: " + 
' '.join(cmd))
   456             p = subprocess.Popen(cmd)
   458         except KeyboardInterrupt:
   464 if __name__ == 
'__main__':
 def get_field_with_default(data_dict, entry, default_value)
def create_models_over_bins_infos(models_over_bins_dict)
def create_belt_part_infos(belt_parts_dict)
def __init__(self, model_type, pose, reference_frame)
def expand_yaml_substitutions(yaml_dict)
def create_order_info(name, order_dict)
def create_drops_info(drops_dict)
def get_required_field(entry_name, data_dict, required_entry)
def replace_type_aliases(model_type)
def __init__(self, arm_type, initial_joint_states)
def create_options_info(options_dict)
def __init__(self, name, sensor_type, pose)
def prepare_arguments(parser)
def prepare_template_data(config_dict)
def create_order_infos(orders_dict)
def create_models_to_spawn_infos(models_to_spawn_dict)
def generate_files(template_data)
def create_pose_info(pose_dict)
def create_arm_info(arm_dict)
def create_model_info(model_name, model_data)
def create_sensor_info(name, sensor_data)
def __init__(self, drop_region_min, drop_region_max)
def create_sensor_infos(sensors_dict)
def __init__(self, model_type, destination)
def __init__(self, xyz, rpy)