From 148e30ececee94b212eaac862eba5615d5843957 Mon Sep 17 00:00:00 2001 From: srd-rd Date: Thu, 21 Dec 2017 16:53:45 +0100 Subject: [PATCH 01/12] Made some changes for ease of use of ipa production plant. --- cob_gazebo/launch/robot.launch | 2 +- cob_gazebo_worlds/launch/ipa-production-plant.xml | 15 +++++++++++++-- .../urdf/ipa-production-plant/sensors.urdf.xacro | 8 ++++---- 3 files changed, 18 insertions(+), 7 deletions(-) diff --git a/cob_gazebo/launch/robot.launch b/cob_gazebo/launch/robot.launch index 2e5ef77f..88e10970 100644 --- a/cob_gazebo/launch/robot.launch +++ b/cob_gazebo/launch/robot.launch @@ -14,6 +14,6 @@ - + diff --git a/cob_gazebo_worlds/launch/ipa-production-plant.xml b/cob_gazebo_worlds/launch/ipa-production-plant.xml index 65c460b2..80c0356f 100644 --- a/cob_gazebo_worlds/launch/ipa-production-plant.xml +++ b/cob_gazebo_worlds/launch/ipa-production-plant.xml @@ -4,6 +4,9 @@ + + + @@ -13,10 +16,18 @@ - - + + + + + + + +- +- + diff --git a/cob_gazebo_worlds/urdf/ipa-production-plant/sensors.urdf.xacro b/cob_gazebo_worlds/urdf/ipa-production-plant/sensors.urdf.xacro index 149bd03c..9265f168 100644 --- a/cob_gazebo_worlds/urdf/ipa-production-plant/sensors.urdf.xacro +++ b/cob_gazebo_worlds/urdf/ipa-production-plant/sensors.urdf.xacro @@ -14,12 +14,12 @@ - - + + - - + + From e309c73531e391dbd1962bdc4d981d702816e4b0 Mon Sep 17 00:00:00 2001 From: srd-rd Date: Fri, 9 Mar 2018 17:04:23 +0100 Subject: [PATCH 02/12] Added parameter multi-robot to decide whether or not to start the controller. --- cob_bringup_sim/launch/robot.launch | 4 +++- cob_gazebo/launch/robot.launch | 2 ++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/cob_bringup_sim/launch/robot.launch b/cob_bringup_sim/launch/robot.launch index 2650224a..db182a16 100644 --- a/cob_bringup_sim/launch/robot.launch +++ b/cob_bringup_sim/launch/robot.launch @@ -9,6 +9,7 @@ + @@ -26,12 +27,13 @@ - + + diff --git a/cob_gazebo/launch/robot.launch b/cob_gazebo/launch/robot.launch index 88e10970..5ef3b1f7 100644 --- a/cob_gazebo/launch/robot.launch +++ b/cob_gazebo/launch/robot.launch @@ -7,10 +7,12 @@ + + From c7bebc250f9e7a5c4af1cb7ed17e08aa532611e1 Mon Sep 17 00:00:00 2001 From: srd-rd Date: Fri, 9 Mar 2018 17:14:20 +0100 Subject: [PATCH 03/12] Added a static sensor launch file with urdf.xacro and changed the mass of the walls in ipp to real values. --- .../launch/spawn_static_sensor.launch | 16 +++++++ .../objects/static_sensor_s300.urdf.xacro | 37 ++++++++++++++ .../ipa-production-plant/walls.urdf.xacro | 48 +++++++++---------- 3 files changed, 77 insertions(+), 24 deletions(-) create mode 100644 cob_gazebo_objects/launch/spawn_static_sensor.launch create mode 100644 cob_gazebo_objects/objects/static_sensor_s300.urdf.xacro diff --git a/cob_gazebo_objects/launch/spawn_static_sensor.launch b/cob_gazebo_objects/launch/spawn_static_sensor.launch new file mode 100644 index 00000000..01a44e88 --- /dev/null +++ b/cob_gazebo_objects/launch/spawn_static_sensor.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/cob_gazebo_objects/objects/static_sensor_s300.urdf.xacro b/cob_gazebo_objects/objects/static_sensor_s300.urdf.xacro new file mode 100644 index 00000000..81d9da24 --- /dev/null +++ b/cob_gazebo_objects/objects/static_sensor_s300.urdf.xacro @@ -0,0 +1,37 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + false + + + diff --git a/cob_gazebo_worlds/urdf/ipa-production-plant/walls.urdf.xacro b/cob_gazebo_worlds/urdf/ipa-production-plant/walls.urdf.xacro index 868f1cbf..c0c82f23 100644 --- a/cob_gazebo_worlds/urdf/ipa-production-plant/walls.urdf.xacro +++ b/cob_gazebo_worlds/urdf/ipa-production-plant/walls.urdf.xacro @@ -6,7 +6,7 @@ - + @@ -37,7 +37,7 @@ - + @@ -69,7 +69,7 @@ - + @@ -101,7 +101,7 @@ - + @@ -133,7 +133,7 @@ - + @@ -164,7 +164,7 @@ - + @@ -196,7 +196,7 @@ - + @@ -229,7 +229,7 @@ - + @@ -261,7 +261,7 @@ - + @@ -293,7 +293,7 @@ - + @@ -325,7 +325,7 @@ - + @@ -357,7 +357,7 @@ - + @@ -389,7 +389,7 @@ - + @@ -421,7 +421,7 @@ - + @@ -453,7 +453,7 @@ - + @@ -485,7 +485,7 @@ - + @@ -517,7 +517,7 @@ - + @@ -549,7 +549,7 @@ - + @@ -581,7 +581,7 @@ - + @@ -613,7 +613,7 @@ - + @@ -645,7 +645,7 @@ - + @@ -677,7 +677,7 @@ - + @@ -709,7 +709,7 @@ - + @@ -741,7 +741,7 @@ - + From 0649c215d587bc806091316f506341ea5ebafba1 Mon Sep 17 00:00:00 2001 From: srd-rd Date: Fri, 4 May 2018 21:40:19 +0200 Subject: [PATCH 04/12] Production plant update --- .../launch/spawn_object_urdf.launch | 6 +++++- cob_gazebo_objects/objects/forklift.urdf | 5 ++++- .../launch/ipa-production-plant.xml | 19 +++++++++++-------- .../ipa-production-plant.urdf.xacro | 4 ++-- .../ipa-production-plant/sensors.urdf.xacro | 2 +- 5 files changed, 23 insertions(+), 13 deletions(-) diff --git a/cob_gazebo_objects/launch/spawn_object_urdf.launch b/cob_gazebo_objects/launch/spawn_object_urdf.launch index 1f1c3fbe..715db08f 100644 --- a/cob_gazebo_objects/launch/spawn_object_urdf.launch +++ b/cob_gazebo_objects/launch/spawn_object_urdf.launch @@ -3,9 +3,13 @@ + + + + - + diff --git a/cob_gazebo_objects/objects/forklift.urdf b/cob_gazebo_objects/objects/forklift.urdf index 690e277a..04b42988 100644 --- a/cob_gazebo_objects/objects/forklift.urdf +++ b/cob_gazebo_objects/objects/forklift.urdf @@ -7,12 +7,15 @@ + 1 + 1 - + + 1 diff --git a/cob_gazebo_worlds/launch/ipa-production-plant.xml b/cob_gazebo_worlds/launch/ipa-production-plant.xml index 80c0356f..cd968d76 100644 --- a/cob_gazebo_worlds/launch/ipa-production-plant.xml +++ b/cob_gazebo_worlds/launch/ipa-production-plant.xml @@ -4,7 +4,7 @@ - + @@ -13,21 +13,24 @@ - + - - + - + + + + -- -- + + diff --git a/cob_gazebo_worlds/urdf/ipa-production-plant/ipa-production-plant.urdf.xacro b/cob_gazebo_worlds/urdf/ipa-production-plant/ipa-production-plant.urdf.xacro index e245dc7e..c3015b84 100644 --- a/cob_gazebo_worlds/urdf/ipa-production-plant/ipa-production-plant.urdf.xacro +++ b/cob_gazebo_worlds/urdf/ipa-production-plant/ipa-production-plant.urdf.xacro @@ -9,14 +9,14 @@ - + - + diff --git a/cob_gazebo_worlds/urdf/ipa-production-plant/sensors.urdf.xacro b/cob_gazebo_worlds/urdf/ipa-production-plant/sensors.urdf.xacro index 9265f168..ff3ceecd 100644 --- a/cob_gazebo_worlds/urdf/ipa-production-plant/sensors.urdf.xacro +++ b/cob_gazebo_worlds/urdf/ipa-production-plant/sensors.urdf.xacro @@ -24,4 +24,4 @@ - + \ No newline at end of file From c0a7206b2d8d03640e2858fdb76bffd5de3e8ef5 Mon Sep 17 00:00:00 2001 From: srd-rd Date: Tue, 29 May 2018 16:51:30 +0200 Subject: [PATCH 05/12] benchmark stuff --- cob_bringup_sim/config/benchmark_config.yaml | 180 ++++ cob_bringup_sim/scripts/benchmark_tool.py | 518 +++++++++++ cob_gazebo_objects/objects/column.urdf | 10 +- cob_gazebo_worlds/launch/ipa-benchmark.xml | 22 + .../launch/ipa-production-plant.xml | 2 +- .../ipa-benchmark.property.xacro | 42 + .../ipa-benchmark/ipa-benchmark.urdf.xacro | 24 + .../urdf/ipa-benchmark/sensors.urdf.xacro | 27 + .../urdf/ipa-benchmark/walls.urdf.xacro | 806 ++++++++++++++++++ 9 files changed, 1625 insertions(+), 6 deletions(-) create mode 100644 cob_bringup_sim/config/benchmark_config.yaml create mode 100755 cob_bringup_sim/scripts/benchmark_tool.py create mode 100644 cob_gazebo_worlds/launch/ipa-benchmark.xml create mode 100644 cob_gazebo_worlds/urdf/ipa-benchmark/ipa-benchmark.property.xacro create mode 100644 cob_gazebo_worlds/urdf/ipa-benchmark/ipa-benchmark.urdf.xacro create mode 100644 cob_gazebo_worlds/urdf/ipa-benchmark/sensors.urdf.xacro create mode 100644 cob_gazebo_worlds/urdf/ipa-benchmark/walls.urdf.xacro diff --git a/cob_bringup_sim/config/benchmark_config.yaml b/cob_bringup_sim/config/benchmark_config.yaml new file mode 100644 index 00000000..12a1d1fb --- /dev/null +++ b/cob_bringup_sim/config/benchmark_config.yaml @@ -0,0 +1,180 @@ +# The inflation radius of the paths [float] +inflation_radius: 1.0 +# The number of rooms [int] +room_number: 4 +# The maximum number of objects to be spawned [float] +max_num_objects: 300 +# The rate at which objects should be changed in hz [float] +spawn_object_rate: 1 +# The number of objects that is supposed to be changed per time-step [int] +num_changed_objects: 20 +# Specifies in which rooms moving objects will be spawned [list, int] +spawn_moving_objects: [0, 1, 2, 3] + +# The paths to the urdf files for the models +models: + box: + package: cob_gazebo_objects + path: objects/box.urdf + column: + package: cob_gazebo_objects + path: objects/column.urdf + +# The boundaries of each room +boundaries: + - room: 0 + start_x: -19.95 + start_y: -10.95 + end_x: 1.95 + end_y: 12.95 + - room: 1 + start_x: 2.05 + start_y: -10.95 + end_x: 27.45 + end_y: 12.95 + - room: 2 + start_x: 2.05 + start_y: -34.95 + end_x: 27.45 + end_y: -11.05 + - room: 3 + start_x: -19.95 + start_y: -34.95 + end_x: 1.95 + end_y: -11.05 + +# The dynamic objects and their respective paths +moving_objects: + - room_id: 0 + type: column + velocity: 0.8 + path_type: polygon + path: [[-13.5, 4.5], [-4.5, 4.5], [-4.5, -4.5], [-13.5, -4.5], [-13.5, 4.5]] + - room_id: 1 + type: column + velocity: 0.8 + path_type: polygon + path: [[8.5, 4.5], [21.0, 4.5], [21.0, 0.0], [8.5, 0.0], [8.5, 4.5]] + - room_id: 1 + type: column + velocity: 0.8 + path_type: polygon + path: [[21.0, -4.5], [8.5, -4.5], [8.5, 0.0], [21.0, 0.0], [21.0, -4.5]] + - room_id: 2 + type: column + velocity: 0.8 + path_type: polygon + path: [[21.0, -28.5], [8.5, -28.5], [8.5, -17.5], [21.0, -17.5], [21.0, -28.5]] + - room_id: 3 + type: column + velocity: 0.8 + path_type: polygon + path: [[-4.5, -17.5], [-4.5, -23.0], [-13.5, -23.0], [-13.5, -17.5], [-4.5, -17.5]] + - room_id: 3 + type: column + velocity: 0.8 + path_type: polygon + path: [[-13.5, -28.5], [-13.5, -23.0], [-4.5, -23.0], [-4.5, -28.5], [-13.5, -28.5]] + +# The paths the robot will travel on sorted by room +paths: + room_0: + - start_x: -9.00 + start_y: -14.50 + end_x: -9.00 + end_y: -7.50 + - start_x: -16.5 + start_y: -7.50 + end_x: -1.50 + end_y: -7.50 + - start_x: -16.5 + start_y: -7.5 + end_x: -16.5 + end_y: 7.5 + - start_x: -16.5 + start_y: 7.5 + end_x: -1.5 + end_y: 7.5 + - start_x: -1.5 + start_y: -7.5 + end_x: -1.5 + end_y: 7.5 + - start_x: -1.5 + start_y: 7.5 + end_x: 5.5 + end_y: 7.5 + room_1: + - start_x: -1.5 + start_y: 7.5 + end_x: 5.5 + end_y: 7.5 + - start_x: 5.50 + start_y: 7.50 + end_x: 24.00 + end_y: 7.50 + - start_x: 24.00 + start_y: -7.5 + end_x: 24.00 + end_y: 7.5 + - start_x: 5.50 + start_y: -7.50 + end_x: 24.00 + end_y: -7.50 + - start_x: 5.50 + start_y: -7.50 + end_x: 5.50 + end_y: 7.50 + - start_x: 14.75 + start_y: -14.50 + end_x: 14.75 + end_y: -7.50 + room_2: + - start_x: 14.75 + start_y: -14.50 + end_x: 14.75 + end_y: -7.50 + - start_x: 5.50 + start_y: -14.50 + end_x: 24.00 + end_y: -14.50 + - start_x: 24.00 + start_y: -31.50 + end_x: 24.00 + end_y: -14.50 + - start_x: 5.50 + start_y: -31.50 + end_x: 24.00 + end_y: -31.50 + - start_x: 5.50 + start_y: -31.50 + end_x: 5.50 + end_y: -14.50 + - start_x: -1.50 + start_y: -23.00 + end_x: 5.50 + end_y: -23.00 + room_3: + - start_x: -1.50 + start_y: -23.00 + end_x: 5.50 + end_y: -23.00 + - start_x: -1.50 + start_y: -31.50 + end_x: -1.50 + end_y: -14.50 + - start_x: -16.50 + start_y: -31.50 + end_x: -1.50 + end_y: -31.50 + - start_x: -16.50 + start_y: -31.50 + end_x: -16.50 + end_y: -14.50 + - start_x: -16.50 + start_y: -14.50 + end_x: -1.50 + end_y: -14.50 + - start_x: -9.00 + start_y: -14.50 + end_x: -9.00 + end_y: -7.50 \ No newline at end of file diff --git a/cob_bringup_sim/scripts/benchmark_tool.py b/cob_bringup_sim/scripts/benchmark_tool.py new file mode 100755 index 00000000..9bd51621 --- /dev/null +++ b/cob_bringup_sim/scripts/benchmark_tool.py @@ -0,0 +1,518 @@ +#!/usr/bin/env python + +import rospy +import rospkg +from gazebo_ros.gazebo_interface import DeleteModelRequest, SpawnModelRequest, SpawnModel, DeleteModel, SetModelState, SetModelStateRequest + +from ipa_navigation_utils import log + +import sys +import yaml +import numpy as np +import subprocess + +ros_packages = rospkg.RosPack() +object_path = ros_packages.get_path('cob_gazebo_objects') + '/objects/' + +### PARAMETERS +CONFIG_FILE = ros_packages.get_path('cob_bringup_sim') + '/config/benchmark_config.yaml' +RADIUS = 0.71 + +### GLOBAL VARIABLES +objects_ = {} +object_ids_ = {} +moving_objects_ = [] + +log.level = log.DEBUG + + +class CONFIG: + """ + Contains the configuration parameters for the benchmark-tool node. + """ + inflation_radius = None + room_number = None + max_num_objects = None + spawn_object_rate = None + num_changed_objects = None + spawn_moving_objects = None + + models = None + room_boundaries = None + moving_objects = None + paths = None + + @classmethod + def load(cls, file_path): + """ + Loads all config parameters from the specified yaml-file. + :param file_path: The yaml-file containing the config. + :type file_path: str + :return: + :rtype: None + """ + with open(file_path) as f: + data = yaml.safe_load(f) + + cls.inflation_radius = data['inflation_radius'] + cls.room_number = data['room_number'] + cls.max_num_objects = data['max_num_objects'] + cls.spawn_object_rate = data['spawn_object_rate'] + cls.num_changed_objects = data['num_changed_objects'] + cls.spawn_moving_objects = data['spawn_moving_objects'] + + cls.models = data['models'] + cls.room_boundaries = data['boundaries'] + cls.moving_objects = data['moving_objects'] + cls.paths = data['paths'] + + for model in cls.models.keys(): + cls.models[model]['path'] = ros_packages.get_path(cls.models[model]['package']) + '/' + \ + cls.models[model]['path'] + + for room in cls.paths: + for path in cls.paths[room]: + path['start_x'] -= cls.inflation_radius + path['start_y'] -= cls.inflation_radius + path['end_x'] += cls.inflation_radius + path['end_y'] += cls.inflation_radius + + @classmethod + def set_inflation_radius(cls, inflation_radius): + """ + Sets the inflation radius to the new value and updates all paths. + :param inflation_radius: The new inflation radius value. + :type inflation_radius: float + :return: + :rtype: None + """ + diff = inflation_radius - cls.inflation_radius + + for room in cls.paths: + for path in room[room.keys()[0]]: + path['start_x'] -= diff + path['start_y'] -= diff + path['end_x'] += diff + path['end_y'] += diff + + cls.inflation_radius = inflation_radius + + +class Object: + def __init__(self, x, y, room_id, radius=0.5): + self.pos = np.array([x, y]) + self.room_id = room_id + self.radius = radius + + +def spawn_moving_objects(): + global moving_objects_ + + log.debug('Spawning moving objects') + + moving_obj_id = 0 + for moving_obj in CONFIG.moving_objects: + if moving_obj['room_id'] not in CONFIG.spawn_moving_objects: + continue + + # Spawn model in Gazebo + model_name = 'moving_' + moving_obj['type'] + '_' + str(moving_obj_id) + obj_pos = np.array(moving_obj['path'][0]) + spawn_model(model_name, CONFIG.models[moving_obj['type']]['path'], obj_pos) + + # Run driver to move object around + new_obj_proc = subprocess.Popen(['rosrun', 'cob_bringup_sim', 'move_object.py', + '--mode='+moving_obj['path_type'], + '--name='+model_name, + '--velocity='+str(moving_obj['velocity']), + '--polygon='+str(moving_obj['path'])]) + moving_objects_.append([model_name, new_obj_proc]) + + moving_obj_id += 1 + + log.info('Successfully spawned moving objects') + + +def spawn_object_loop(radius, type=None): + """ + Loops until node terminates and spawns objects dynamically at the given rate. + :param radius: The radius of the objects to spawn. + :type radius: float + :param type: The type of the objects to spawn. + :type type: str + :return: + :rtype: None + """ + while not rospy.is_shutdown(): + for i in range(CONFIG.num_changed_objects): + log.debug('Changing another spawned object') + # Select randomly a spawned object to delete + spawned_object_ids = np.where(object_ids_[type]>0)[0] + if spawned_object_ids.shape[0] <= 0: + log.error('No objects spawned yet, shutting down now') + return + obj_id = np.random.choice(spawned_object_ids, 1)[0] + model_name = type + '_' + str(obj_id) + + # # Delete selected model + # delete_model(del_model_name) + # + # # Spawn a new object + # spawn_object(type, np.random.randint(CONFIG.room_number), radius) + + room_id = np.random.randint(CONFIG.room_number) + obj_pos = get_new_coordinates(room_id, radius) + if len(obj_pos) <= 0: + continue + + move_model(model_name, obj_pos) + + objects_[type][obj_id] = np.copy(obj_pos) + + rospy.sleep(CONFIG.spawn_object_rate) + + +def get_new_coordinates(room_id, radius, threshold=1000): + coord_check = False + threshold = 100 + count = 0 + + while not coord_check: + obj_pos = generate_coordinates(room_id, radius) + + coord_check = check_coordinates(obj_pos, room_id, radius) + + count += 1 + if count >= threshold: + log.warn('Could not find a valid position for model with type \'{}\' in room {}'.format(type, room_id)) + log.warn('Aborting now') + return [] + + return obj_pos + + +def spawn_object(type, room_id, radius, name=None): + """ + Spawns an object with the given type in the specified room. + :param type: The type of the the object to spawn. + :type type: str + :param room_id: The room-id for the room the object should be spawned in. + :type room_id: int + :param radius: The radius of the object to spawn. + :type radius: float + :return: + :rtype: None + """ + global objects_ + + obj_pos = get_new_coordinates(room_id, radius) + if len(obj_pos) <= 0: + return + + obj_id = np.argmax(object_ids_[type]==0) + model_name = type + '_' + str(obj_id) + + # Set used object id to true (1) + object_ids_[type][obj_id] = 1 + + # Set coordinates for object + objects_[type][obj_id] = obj_pos + + spawn_model(model_name, CONFIG.models[type]['path'], obj_pos) + + +def check_coordinates(new_obj_pos, room_id, radius): + """ + Performs a check on new object coordinates. The function verifies, that the position lies not within the boundaries + of another object or a robot path. + :param new_obj_pos: The position (x, y) of the new object. + :type new_obj_pos: ndarray + :param room_id: The id of the room, where the object is supposed to be spawned. + :type room_id: int + :param radius: The maximum radius of the object. + :type radius: float + :return: True if the object is collision-free, False otherwise. + :rtype: bool + """ + # Check all objects within the room + for type in objects_: + for obj_pos in objects_[type]: + dist = np.linalg.norm(new_obj_pos - obj_pos) + if dist <= radius: + log.info('New Object didn\'t pass the object location check [room={}, pos=({}, {}), radius={}]'.format( + room_id, new_obj_pos[0], new_obj_pos[1], radius)) + return False + + # Check for all paths in the room + for path in CONFIG.paths['room_'+str(room_id)]: + in_x = path['start_x']-radius <= new_obj_pos[0] <= path['end_x']+radius + in_y = path['start_y']-radius <= new_obj_pos[1] <= path['end_y']+radius + + if in_x and in_y: + log.debug('New Object didn\'t pass the robot path check [room={}, pos=({}, {}), radius={}]'.format( + room_id, new_obj_pos[0], new_obj_pos[1], radius)) + return False + + # Check for moving obj paths + for moving_obj in CONFIG.moving_objects: + if moving_obj['room_id'] not in CONFIG.spawn_moving_objects: + continue + + for i, start in enumerate(moving_obj['path'][:-1]): + end = moving_obj['path'][i+1] + if start[0] <= end[0]: + start_x = start[0] + end_x = end[0] + else: + start_x = end[0] + end_x = start[0] + if start[1] <= end[1]: + start_y = start[1] + end_y = end[1] + else: + start_y = end[1] + end_y = start[1] + + in_x = start_x - radius*2 <= new_obj_pos[0] <= end_x + radius*2 + in_y = start_y - radius*2 <= new_obj_pos[1] <= end_y + radius*2 + + if in_x and in_y: + log.debug('New Object didn\'t pass the moving object path check [room={}, pos=({}, {}), radius={}]'.format( + room_id, new_obj_pos[0], new_obj_pos[1], radius)) + return False + + log.debug('New Object passed the check [room={}, pos=({}, {}), radius={}]'.format( + room_id, new_obj_pos[0], new_obj_pos[1], radius)) + + return True + + +def generate_coordinates(room_id, radius): + """ + Randomly generates a set of coordinates (x, y) that lie within the given rooms boundaries. + :param room_id: The id of the room where the coordinates are supposed to be in. + :type room_id: int + :param radius: The radius of the object, the coordinates are generated for. + :type radius: float + :return: The new coordinates (x, y). + :rtype: ndarray + """ + x = np.random.uniform(CONFIG.room_boundaries[room_id]['start_x']+radius, + CONFIG.room_boundaries[room_id]['end_x']-radius) + y = np.random.uniform(CONFIG.room_boundaries[room_id]['start_y']+radius, + CONFIG.room_boundaries[room_id]['end_y']-radius) + + return np.array([x, y]) + + +def spawn_init_objects(type, radius): + """ + Spawns initially the number of objects specified in the config. + :param type: The type of the object to be spawned. + :type type: str + :param radius: The maximum radius of the object to be spawned. + :type radius: float + :return: + :rtype: None + """ + log.debug('Spawning {} initial objects'.format(CONFIG.max_num_objects)) + for i in range(CONFIG.max_num_objects): + spawn_object(type, np.random.randint(CONFIG.room_number), radius) + + log.info('Spawned {} initial objects'.format(CONFIG.max_num_objects)) + + +def delete_all_objects(): + """ + Deletes all objects that were created from this node. + :return: + :rtype: None + """ + global moving_objects_ + + log.debug('Deleting all dynamic objects') + for dyn_obj in moving_objects_: + delete_model(dyn_obj[0]) + + log.info('Successfully deleted all dynamic objects') + + log.debug('Deleting all static objects') + for obj_type in object_ids_: + for i in range(len(object_ids_[obj_type])): + if object_ids_[obj_type][i] > 0: + delete_model(obj_type + '_' + str(i)) + + log.info('Successfully deleted all static objects') + + +def move_model(model_name, new_pos): + log.debug('Waiting for service: /gazebo/set_model_state') + rospy.wait_for_service('/gazebo/set_model_state', timeout=2.0) + try: + log.debug('Trying to move model \'{}\' to position {}'.format(model_name, new_pos)) + req = SetModelStateRequest() + req.model_state.model_name = model_name + req.model_state.pose.position.x = new_pos[0] + req.model_state.pose.position.y = new_pos[1] + srv_mov_scanner = rospy.ServiceProxy('/gazebo/set_model_state', SetModelState) + ret = srv_mov_scanner(req) + if not ret.success: + log.warn('Could not move model \'{}\' because an error occured during service call'.format(model_name)) + return + except rospy.ServiceException, e: + log.warn("Service call failed: %s" % e) + return + + log.info('Moved model \'{}\' to new position at [{:.2f}, {:.2f}]'.format(model_name, new_pos[0], new_pos[1])) + + return + + +def delete_model(model_name): + """ + Deletes the given model from the current gazebo simulation. + :param model_name: The name of the model to be removed. + :type model_name: str + :return: + :rtype: None + """ + log.debug('Waiting for service: /gazebo/delete_model') + rospy.wait_for_service('/gazebo/delete_model', timeout=2.0) + try: + log.debug('Trying to delete model: {}'.format(model_name)) + req = DeleteModelRequest() + req.model_name = str(model_name) + srv_del_scanner = rospy.ServiceProxy('/gazebo/delete_model', DeleteModel) + ret = srv_del_scanner(req) + if not ret.success: + log.warn('Could not delete model \'{}\' because an error occured during service call'.format(model_name)) + return + except rospy.ServiceException, e: + log.warn("Service call failed: %s" % e) + return + + log.info('Deleted existing model \'{}\''.format(model_name)) + + # Reset object id to 0 + obj_id = int(model_name.split('_')[-1]) + obj_name = model_name.split('_')[0] + + if not 'moving' in model_name: + object_ids_[obj_name][obj_id] = 0 + + return + + +def spawn_model(model_name, urdf_path, position=None): + """ + Spawns the specified model in the current gazebo simulation. + :param model_name: The name of the model to be spawned. + :type model_name: str + :param urdf_path: The path of the model to be spawned. + :type urdf_path: str + :param position: The position (x, y) of the model to be spawned. + :type position: ndarray + :return: + :rtype: None + """ + log.info('Spawning new model \'{}\' at position [{}, {}]'.format(model_name, position[0], position[1])) + rospy.wait_for_service('/gazebo/spawn_urdf_model', timeout=2.0) + try: + req = SpawnModelRequest() + req.model_name = model_name + + # Load Model XML + f = open(urdf_path, 'r') + req.model_xml = f.read() + if req.model_xml == "": + rospy.logerr("Error: file is empty %s", urdf_path) + sys.exit(0) + + if position is not None: + req.initial_pose.position.x = position[0] + req.initial_pose.position.y = position[1] + + srv_del_scanner = rospy.ServiceProxy('/gazebo/spawn_urdf_model', SpawnModel) + ret = srv_del_scanner(req) + if ret.success: + log.info('Successfully spawned model \'{}\'.'.format(model_name)) + else: + log.warn('Could not spawn model \'{}\'.'.format(model_name)) + except rospy.ServiceException, e: + log.warn("Service call failed: %s" % e) + + +def shutdown_moving_objects(): + global moving_objects_ + + log.debug('Shutting down drivers for moving objects') + + for moving_obj in moving_objects_: + moving_obj[1].terminate() + moving_obj[1].wait() + log.info('Terminated driver for moving object: '+moving_obj[0]) + + log.info('Successfully shut down all drivers for moving objects') + + +def on_shutdown(): + log.info('Shutting down now') + + shutdown_moving_objects() + + delete_all_objects() + + log.info('Shutdown complete') + + +def init_ros(): + """ + Initializes ros with subscribers, publishers, etc. + :return: + :rtype: None + """ + rospy.init_node('benchmark_tool') + + rospy.on_shutdown(on_shutdown) + + +def initialize(): + """ + Initializes the node including ros and the config. + :return: + :rtype: None + """ + global objects_, object_ids_ + + init_ros() + + CONFIG.load(CONFIG_FILE) + + # objects_ = [[] for i in range(CONFIG.room_number) + for obj_name in CONFIG.models.keys(): + objects_[obj_name] = np.zeros((CONFIG.max_num_objects, 2)) + object_ids_[obj_name] = np.zeros(CONFIG.max_num_objects) + + log.info('Done initializing') + + +def main(): + """ + The main function of the node. Contains the core functionality. + :return: + :rtype: None + """ + initialize() + + spawn_init_objects('box', RADIUS) + + if len(CONFIG.spawn_moving_objects) > 0: + spawn_moving_objects() + + spawn_object_loop(RADIUS, 'box') + + delete_all_objects() + + +if __name__ == '__main__': + main() diff --git a/cob_gazebo_objects/objects/column.urdf b/cob_gazebo_objects/objects/column.urdf index 224e052a..95ca4adb 100644 --- a/cob_gazebo_objects/objects/column.urdf +++ b/cob_gazebo_objects/objects/column.urdf @@ -7,19 +7,19 @@ - + - + - + - + - true + false diff --git a/cob_gazebo_worlds/launch/ipa-benchmark.xml b/cob_gazebo_worlds/launch/ipa-benchmark.xml new file mode 100644 index 00000000..6ff49752 --- /dev/null +++ b/cob_gazebo_worlds/launch/ipa-benchmark.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/cob_gazebo_worlds/launch/ipa-production-plant.xml b/cob_gazebo_worlds/launch/ipa-production-plant.xml index cd968d76..8ec87e61 100644 --- a/cob_gazebo_worlds/launch/ipa-production-plant.xml +++ b/cob_gazebo_worlds/launch/ipa-production-plant.xml @@ -31,6 +31,6 @@ - + diff --git a/cob_gazebo_worlds/urdf/ipa-benchmark/ipa-benchmark.property.xacro b/cob_gazebo_worlds/urdf/ipa-benchmark/ipa-benchmark.property.xacro new file mode 100644 index 00000000..21857115 --- /dev/null +++ b/cob_gazebo_worlds/urdf/ipa-benchmark/ipa-benchmark.property.xacro @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + 24 + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/cob_gazebo_worlds/urdf/ipa-benchmark/ipa-benchmark.urdf.xacro b/cob_gazebo_worlds/urdf/ipa-benchmark/ipa-benchmark.urdf.xacro new file mode 100644 index 00000000..f6eb8843 --- /dev/null +++ b/cob_gazebo_worlds/urdf/ipa-benchmark/ipa-benchmark.urdf.xacro @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + diff --git a/cob_gazebo_worlds/urdf/ipa-benchmark/sensors.urdf.xacro b/cob_gazebo_worlds/urdf/ipa-benchmark/sensors.urdf.xacro new file mode 100644 index 00000000..ff3ceecd --- /dev/null +++ b/cob_gazebo_worlds/urdf/ipa-benchmark/sensors.urdf.xacro @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/cob_gazebo_worlds/urdf/ipa-benchmark/walls.urdf.xacro b/cob_gazebo_worlds/urdf/ipa-benchmark/walls.urdf.xacro new file mode 100644 index 00000000..2cee68ad --- /dev/null +++ b/cob_gazebo_worlds/urdf/ipa-benchmark/walls.urdf.xacro @@ -0,0 +1,806 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wall_floor_05 + + + + + + + + + + + + + \ No newline at end of file From 84cfbb0af1d367058ed744d6eaab2d83e4f8f372 Mon Sep 17 00:00:00 2001 From: srd-rd Date: Tue, 29 May 2018 18:08:04 +0200 Subject: [PATCH 06/12] added dynamic objects and control over spawn rate --- cob_bringup_sim/config/benchmark_config.yaml | 62 ++++++++++++++++++-- cob_bringup_sim/scripts/benchmark_tool.py | 16 ++++- 2 files changed, 70 insertions(+), 8 deletions(-) diff --git a/cob_bringup_sim/config/benchmark_config.yaml b/cob_bringup_sim/config/benchmark_config.yaml index 12a1d1fb..85c801e2 100644 --- a/cob_bringup_sim/config/benchmark_config.yaml +++ b/cob_bringup_sim/config/benchmark_config.yaml @@ -3,9 +3,11 @@ inflation_radius: 1.0 # The number of rooms [int] room_number: 4 # The maximum number of objects to be spawned [float] -max_num_objects: 300 -# The rate at which objects should be changed in hz [float] +max_num_objects: 10 +# The rate at which objects are spawned initially in hz [float] spawn_object_rate: 1 +# The rate at which objects are moved during runtime in hz [float] +move_object_rate: 1 # The number of objects that is supposed to be changed per time-step [int] num_changed_objects: 20 # Specifies in which rooms moving objects will be spawned [list, int] @@ -50,6 +52,21 @@ moving_objects: velocity: 0.8 path_type: polygon path: [[-13.5, 4.5], [-4.5, 4.5], [-4.5, -4.5], [-13.5, -4.5], [-13.5, 4.5]] + - room_id: 0 + type: column + velocity: 0.8 + path_type: polygon + path: [[-4.5, 4.5], [-4.5, -4.5], [-13.5, -4.5], [-13.5, 4.5], [-13.5, 4.5]] + - room_id: 0 + type: column + velocity: 0.8 + path_type: polygon + path: [[-4.5, -4.5], [-13.5, -4.5], [-13.5, 4.5], [-13.5, 4.5], [-4.5, 4.5]] + - room_id: 0 + type: column + velocity: 0.8 + path_type: polygon + path: [[-13.5, -4.5], [-13.5, 4.5], [-13.5, 4.5], [-4.5, 4.5], [-4.5, -4.5]] - room_id: 1 type: column velocity: 0.8 @@ -59,22 +76,57 @@ moving_objects: type: column velocity: 0.8 path_type: polygon - path: [[21.0, -4.5], [8.5, -4.5], [8.5, 0.0], [21.0, 0.0], [21.0, -4.5]] + path: [[21.0, 4.5], [21.0, -4.5], [8.5, -4.5], [8.5, 4.5], [21.0, 4.5]] + - room_id: 1 + type: column + velocity: 0.8 + path_type: polygon + path: [[21.0, -4.5], [8.5, -4.5], [8.5, 4.5], [21.0, 4.5], [21.0, 4.5]] + - room_id: 1 + type: column + velocity: 0.8 + path_type: polygon + path: [[8.5, -4.5], [8.5, 4.5], [21.0, 4.5], [21.0, 4.5], [21.0, -4.5]] - room_id: 2 type: column velocity: 0.8 path_type: polygon path: [[21.0, -28.5], [8.5, -28.5], [8.5, -17.5], [21.0, -17.5], [21.0, -28.5]] + - room_id: 2 + type: column + velocity: 0.8 + path_type: polygon + path: [[8.5, -28.5], [8.5, -17.5], [21.0, -17.5], [21.0, -28.5], [21.0, -28.5]] + - room_id: 2 + type: column + velocity: 0.8 + path_type: polygon + path: [[8.5, -17.5], [21.0, -17.5], [21.0, -28.5], [21.0, -28.5], [8.5, -28.5]] + - room_id: 2 + type: column + velocity: 0.8 + path_type: polygon + path: [[21.0, -17.5], [21.0, -28.5], [21.0, -28.5], [8.5, -28.5], [8.5, -17.5]] + - room_id: 3 + type: column + velocity: 0.8 + path_type: polygon + path: [[-4.5, -17.5], [-4.5, -28.5], [-13.5, -28.5], [-13.5, -17.5], [-4.5, -17.5]] + - room_id: 3 + type: column + velocity: 0.8 + path_type: polygon + path: [[-4.5, -28.5], [-13.5, -28.5], [-13.5, -17.5], [-4.5, -17.5],[-4.5, -17.5]] - room_id: 3 type: column velocity: 0.8 path_type: polygon - path: [[-4.5, -17.5], [-4.5, -23.0], [-13.5, -23.0], [-13.5, -17.5], [-4.5, -17.5]] + path: [[-13.5, -28.5], [-13.5, -17.5], [-4.5, -17.5],[-4.5, -17.5], [-4.5, -28.5]] - room_id: 3 type: column velocity: 0.8 path_type: polygon - path: [[-13.5, -28.5], [-13.5, -23.0], [-4.5, -23.0], [-4.5, -28.5], [-13.5, -28.5]] + path: [[-13.5, -17.5], [-4.5, -17.5],[-4.5, -17.5], [-4.5, -28.5], [-13.5, -28.5]] # The paths the robot will travel on sorted by room paths: diff --git a/cob_bringup_sim/scripts/benchmark_tool.py b/cob_bringup_sim/scripts/benchmark_tool.py index 9bd51621..84754886 100755 --- a/cob_bringup_sim/scripts/benchmark_tool.py +++ b/cob_bringup_sim/scripts/benchmark_tool.py @@ -33,9 +33,10 @@ class CONFIG: inflation_radius = None room_number = None max_num_objects = None - spawn_object_rate = None + move_object_rate = None num_changed_objects = None spawn_moving_objects = None + spawn_object_rate = None models = None room_boundaries = None @@ -57,9 +58,10 @@ def load(cls, file_path): cls.inflation_radius = data['inflation_radius'] cls.room_number = data['room_number'] cls.max_num_objects = data['max_num_objects'] - cls.spawn_object_rate = data['spawn_object_rate'] + cls.move_object_rate = data['move_object_rate'] cls.num_changed_objects = data['num_changed_objects'] cls.spawn_moving_objects = data['spawn_moving_objects'] + cls.spawn_object_rate = data['spawn_object_rate'] cls.models = data['models'] cls.room_boundaries = data['boundaries'] @@ -169,7 +171,7 @@ def spawn_object_loop(radius, type=None): objects_[type][obj_id] = np.copy(obj_pos) - rospy.sleep(CONFIG.spawn_object_rate) + rospy.sleep(CONFIG.move_object_rate) def get_new_coordinates(room_id, radius, threshold=1000): @@ -203,6 +205,8 @@ def spawn_object(type, room_id, radius, name=None): :return: :rtype: None """ + start_time = rospy.get_rostime() + global objects_ obj_pos = get_new_coordinates(room_id, radius) @@ -220,6 +224,12 @@ def spawn_object(type, room_id, radius, name=None): spawn_model(model_name, CONFIG.models[type]['path'], obj_pos) + # Control spawn rate + dur = rospy.get_rostime() - start_time + delta = dur - rospy.Duration.from_sec(1/CONFIG.spawn_object_rate) + if delta.to_sec() > 0: + rospy.sleep(delta) + def check_coordinates(new_obj_pos, room_id, radius): """ From 9f74ed7b790befaff0de845742ba3b51d9c5b1a2 Mon Sep 17 00:00:00 2001 From: srd-rd Date: Tue, 5 Jun 2018 09:21:00 +0200 Subject: [PATCH 07/12] changes in benchmark tool by srd-rd --- cob_bringup_sim/scripts/benchmark_tool.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/cob_bringup_sim/scripts/benchmark_tool.py b/cob_bringup_sim/scripts/benchmark_tool.py index 84754886..7a2aa044 100755 --- a/cob_bringup_sim/scripts/benchmark_tool.py +++ b/cob_bringup_sim/scripts/benchmark_tool.py @@ -31,6 +31,7 @@ class CONFIG: Contains the configuration parameters for the benchmark-tool node. """ inflation_radius = None + rooms = None room_number = None max_num_objects = None move_object_rate = None @@ -56,7 +57,8 @@ def load(cls, file_path): data = yaml.safe_load(f) cls.inflation_radius = data['inflation_radius'] - cls.room_number = data['room_number'] + cls.rooms = data['rooms'] + cls.room_number = len(cls.rooms) cls.max_num_objects = data['max_num_objects'] cls.move_object_rate = data['move_object_rate'] cls.num_changed_objects = data['num_changed_objects'] @@ -162,7 +164,7 @@ def spawn_object_loop(radius, type=None): # # Spawn a new object # spawn_object(type, np.random.randint(CONFIG.room_number), radius) - room_id = np.random.randint(CONFIG.room_number) + room_id = CONFIG.rooms[np.random.randint(CONFIG.room_number)] obj_pos = get_new_coordinates(room_id, radius) if len(obj_pos) <= 0: continue @@ -226,7 +228,7 @@ def spawn_object(type, room_id, radius, name=None): # Control spawn rate dur = rospy.get_rostime() - start_time - delta = dur - rospy.Duration.from_sec(1/CONFIG.spawn_object_rate) + delta = rospy.Duration.from_sec(1/CONFIG.spawn_object_rate) - dur if delta.to_sec() > 0: rospy.sleep(delta) @@ -327,7 +329,7 @@ def spawn_init_objects(type, radius): """ log.debug('Spawning {} initial objects'.format(CONFIG.max_num_objects)) for i in range(CONFIG.max_num_objects): - spawn_object(type, np.random.randint(CONFIG.room_number), radius) + spawn_object(type, CONFIG.rooms[np.random.randint(CONFIG.room_number)], radius) log.info('Spawned {} initial objects'.format(CONFIG.max_num_objects)) From f304f6fbfa3dac97a940bb34c1c0e60d58596a8c Mon Sep 17 00:00:00 2001 From: srd-rd Date: Wed, 13 Jun 2018 21:49:25 +0200 Subject: [PATCH 08/12] Set static sensor height. --- cob_gazebo_objects/launch/spawn_static_sensor.launch | 2 +- cob_gazebo_worlds/launch/ipa-production-plant.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cob_gazebo_objects/launch/spawn_static_sensor.launch b/cob_gazebo_objects/launch/spawn_static_sensor.launch index 01a44e88..8c44f660 100644 --- a/cob_gazebo_objects/launch/spawn_static_sensor.launch +++ b/cob_gazebo_objects/launch/spawn_static_sensor.launch @@ -2,7 +2,7 @@ - + diff --git a/cob_gazebo_worlds/launch/ipa-production-plant.xml b/cob_gazebo_worlds/launch/ipa-production-plant.xml index 8ec87e61..d8680bce 100644 --- a/cob_gazebo_worlds/launch/ipa-production-plant.xml +++ b/cob_gazebo_worlds/launch/ipa-production-plant.xml @@ -31,6 +31,6 @@ - + From 5f2e82e26c556bdd9d1bc4c80a42d7a0c0a33beb Mon Sep 17 00:00:00 2001 From: srd-rd Date: Thu, 21 Jun 2018 09:58:01 +0200 Subject: [PATCH 09/12] latest changes from srd-rd --- cob_gazebo_worlds/launch/ipa-production-plant.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cob_gazebo_worlds/launch/ipa-production-plant.xml b/cob_gazebo_worlds/launch/ipa-production-plant.xml index d8680bce..8ec87e61 100644 --- a/cob_gazebo_worlds/launch/ipa-production-plant.xml +++ b/cob_gazebo_worlds/launch/ipa-production-plant.xml @@ -31,6 +31,6 @@ - + From b95f08639d81441aeb5c01d674fdfab3ce2c9d8b Mon Sep 17 00:00:00 2001 From: srd-rd Date: Mon, 25 Jun 2018 09:45:34 +0200 Subject: [PATCH 10/12] latest changes srd-rd --- cob_gazebo_worlds/launch/ipa-production-plant.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cob_gazebo_worlds/launch/ipa-production-plant.xml b/cob_gazebo_worlds/launch/ipa-production-plant.xml index 8ec87e61..b2162b27 100644 --- a/cob_gazebo_worlds/launch/ipa-production-plant.xml +++ b/cob_gazebo_worlds/launch/ipa-production-plant.xml @@ -31,6 +31,6 @@ - + From 45491b0871a3e7dd42eaa3e2f97f41461152c77c Mon Sep 17 00:00:00 2001 From: srd-rd Date: Tue, 31 Jul 2018 12:17:48 +0200 Subject: [PATCH 11/12] Added additional moving objects to ipp. --- cob_gazebo_worlds/launch/ipa-production-plant.xml | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/cob_gazebo_worlds/launch/ipa-production-plant.xml b/cob_gazebo_worlds/launch/ipa-production-plant.xml index b2162b27..5d077c16 100644 --- a/cob_gazebo_worlds/launch/ipa-production-plant.xml +++ b/cob_gazebo_worlds/launch/ipa-production-plant.xml @@ -23,14 +23,21 @@ --> - + - + + - + + + + + + + - + From 331754e38e53c813fc3195f439707f5e27574fa5 Mon Sep 17 00:00:00 2001 From: srd-rd Date: Tue, 25 Sep 2018 10:02:35 +0200 Subject: [PATCH 12/12] Reverted personal changes --- cob_gazebo/launch/robot.launch | 2 +- .../launch/ipa-production-plant.xml | 31 +++---------------- 2 files changed, 6 insertions(+), 27 deletions(-) diff --git a/cob_gazebo/launch/robot.launch b/cob_gazebo/launch/robot.launch index 5ef3b1f7..e3d9fb8e 100644 --- a/cob_gazebo/launch/robot.launch +++ b/cob_gazebo/launch/robot.launch @@ -16,6 +16,6 @@ - + diff --git a/cob_gazebo_worlds/launch/ipa-production-plant.xml b/cob_gazebo_worlds/launch/ipa-production-plant.xml index 5d077c16..0956d4e9 100644 --- a/cob_gazebo_worlds/launch/ipa-production-plant.xml +++ b/cob_gazebo_worlds/launch/ipa-production-plant.xml @@ -4,40 +4,19 @@ - - - - + - - - - - - - - - - - - - - - - - - - + - + \ No newline at end of file