Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Harmonic release and ECS refactor #483

Merged
merged 11 commits into from
May 29, 2024
46 changes: 12 additions & 34 deletions rmf_building_map_tools/building_map/building.py
Original file line number Diff line number Diff line change
Expand Up @@ -394,15 +394,9 @@ def generate_nav_graphs(self):
nav_graphs[f'{i}'] = g
return nav_graphs

def generate_sdf_world(self, options):
def generate_sdf_world(self):
""" Return an etree of this Building in SDF starting from a template"""
print(f'generator options: {options}')
if 'gazebo' in options:
template_name = 'gz_world.sdf'
elif 'ignition' in options:
template_name = 'ign_world.sdf'
else:
raise RuntimeError("expected either gazebo or ignition in options")
template_name = 'gz_world.sdf'

template_path = os.path.join(
get_package_share_directory('rmf_building_map_tools'),
Expand All @@ -414,7 +408,7 @@ def generate_sdf_world(self, options):

for level_name, level in self.levels.items():
level.generate_sdf_models(world) # todo: a better name
level.generate_doors(world, options)
level.generate_doors(world)

level_include_ele = SubElement(world, 'include')
level_model_name = f'{self.name}_{level_name}'
Expand All @@ -436,7 +430,7 @@ def generate_sdf_world(self, options):
print(f'[{lift_name}] is not serving any floor, ignoring.')
continue
lift.generate_shaft_doors(world)
lift.generate_cabin(world, options)
lift.generate_cabin(world)

charger_waypoints_ele = SubElement(
world,
Expand Down Expand Up @@ -487,30 +481,14 @@ def generate_sdf_world(self, options):
else:
camera_pose = f'{c[0]} {c[1]-20} 10 0 0.6 1.57'
# add floor-toggle GUI plugin parameters
if 'gazebo' in options:
camera_pose_ele = gui_ele.find('camera').find('pose')
camera_pose_ele.text = camera_pose

toggle_charge_ele = SubElement(
gui_ele,
'plugin',
{'name': 'toggle_charging',
'filename': 'libtoggle_charging.so'})

toggle_floors_ele = SubElement(
gui_ele,
'plugin',
{'name': 'toggle_floors', 'filename': 'libtoggle_floors.so'})

elif 'ignition' in options:
plugin_ele = gui_ele.find('.//plugin[@filename="GzScene3D"]')
camera_pose_ele = plugin_ele.find('camera_pose')
camera_pose_ele.text = camera_pose

toggle_floors_ele = SubElement(
gui_ele,
'plugin',
{'name': 'toggle_floors', 'filename': 'toggle_floors'})
plugin_ele = gui_ele.find('.//plugin[@filename="MinimalScene"]')
camera_pose_ele = plugin_ele.find('camera_pose')
camera_pose_ele.text = camera_pose

toggle_floors_ele = SubElement(
gui_ele,
'plugin',
{'name': 'toggle_floors', 'filename': 'toggle_floors'})

for level_name, level in self.levels.items():
floor_ele = SubElement(
Expand Down
13 changes: 6 additions & 7 deletions rmf_building_map_tools/building_map/doors/door.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,14 +29,14 @@ def __init__(self, door_edge, level_elevation=0.0):
static_ele = SubElement(self.model_ele, 'static')
static_ele.text = 'true'

def generate_section(self, name, width, x_offset, options):
def generate_section(self, name, width, x_offset):
pose_ele = Element('pose')
pose_ele.text = f'{x_offset} 0 {self.height/2+0.01} 0 0 0'
size = [width, self.thickness, self.height]
link_ele = box_link(name,
size,
pose_ele,
material=door_material(options),
material=door_material(),
bitmask='0x02')

mass = 50.0
Expand All @@ -54,8 +54,8 @@ def generate_section(self, name, width, x_offset, options):
self.model_ele.append(link_ele)
return link_ele

def generate_sliding_section(self, name, width, x_offset, bounds, options):
self.generate_section(name, width, x_offset, options)
def generate_sliding_section(self, name, width, x_offset, bounds):
self.generate_section(name, width, x_offset)

self.model_ele.append(joint(f'{name}_joint',
'prismatic',
Expand Down Expand Up @@ -83,10 +83,9 @@ def generate_swing_section(
x_offset,
bounds,
axis_pose,
axis,
options
axis
):
self.generate_section(name, width, x_offset, options)
self.generate_section(name, width, x_offset)

pose_ele = Element('pose')
pose_ele.text = f'{axis_pose[0]} {axis_pose[1]} {axis_pose[2]} 0 0 0'
Expand Down
21 changes: 11 additions & 10 deletions rmf_building_map_tools/building_map/doors/double_sliding_door.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ def __init__(self, door_edge, level_elevation):
if 'right_left_ratio' in door_edge.params:
self.right_left_ratio = door_edge.params['right_left_ratio'].value

def generate(self, world_ele, options):
def generate(self, world_ele):
right_segment_length = \
(self.right_left_ratio / (1 + self.right_left_ratio)) * self.length
left_segment_length = self.length - right_segment_length
Expand All @@ -18,32 +18,33 @@ def generate(self, world_ele, options):
'right',
right_segment_length - 0.01,
self.length / 2 - right_segment_length / 2,
(0.0, right_segment_length),
options)
(0.0, right_segment_length))

self.generate_sliding_section(
'left',
left_segment_length - 0.01,
-self.length / 2 + left_segment_length / 2,
(-left_segment_length, 0.0),
options)
(-left_segment_length, 0.0))

if not self.plugin == 'none':
plugin_ele = SubElement(self.model_ele, 'plugin')
plugin_ele.set('name', 'door')
plugin_ele.set('filename', 'libdoor.so')
plugin_ele.set('name', 'register_component')
plugin_ele.set('filename', 'libregister_component.so')
component_ele = SubElement(plugin_ele, 'component')
component_ele.set('name', 'Door')
plugin_params = {
'v_max_door': '0.2',
'a_max_door': '0.2',
'a_nom_door': '0.08',
'dx_min_door': '0.001',
'f_max_door': '100.0'
'f_max_door': '100.0',
'ros_interface': 'true'
}
for param_name, param_value in plugin_params.items():
ele = SubElement(plugin_ele, param_name)
ele = SubElement(component_ele, param_name)
ele.text = param_value

door_ele = SubElement(plugin_ele, 'door')
door_ele = SubElement(component_ele, 'door')
door_ele.set('name', self.name)
door_ele.set('type', 'DoubleSlidingDoor')
door_ele.set('left_joint_name', 'left_joint')
Expand Down
21 changes: 11 additions & 10 deletions rmf_building_map_tools/building_map/doors/double_swing_door.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ def __init__(self, door_edge, level_elevation):
if 'right_left_ratio' in door_edge.params:
self.right_left_ratio = door_edge.params['right_left_ratio'].value

def generate(self, world_ele, options):
def generate(self, world_ele):
right_segment_length = \
(self.right_left_ratio / (1 + self.right_left_ratio)) * self.length
left_segment_length = self.length - right_segment_length
Expand All @@ -34,34 +34,35 @@ def generate(self, world_ele, options):
x_offsets[0],
bounds[0],
axis_pose[0],
axis,
options)
axis)

self.generate_swing_section(
'left',
left_segment_length - 0.01,
x_offsets[1],
bounds[1],
axis_pose[1],
axis,
options)
axis)

if not self.plugin == 'none':
plugin_ele = SubElement(self.model_ele, 'plugin')
plugin_ele.set('name', 'door')
plugin_ele.set('filename', 'libdoor.so')
plugin_ele.set('name', 'register_component')
plugin_ele.set('filename', 'libregister_component.so')
component_ele = SubElement(plugin_ele, 'component')
component_ele.set('name', 'Door')
plugin_params = {
'v_max_door': '0.5',
'a_max_door': '0.3',
'a_nom_door': '0.15',
'dx_min_door': '0.01',
'f_max_door': '500.0'
'f_max_door': '500.0',
'ros_interface': 'true'
}
for param_name, param_value in plugin_params.items():
ele = SubElement(plugin_ele, param_name)
ele = SubElement(component_ele, param_name)
ele.text = param_value

door_ele = SubElement(plugin_ele, 'door')
door_ele = SubElement(component_ele, 'door')
door_ele.set('name', self.name)
door_ele.set('type', 'DoubleSwingDoor')
door_ele.set('left_joint_name', 'left_joint')
Expand Down
18 changes: 10 additions & 8 deletions rmf_building_map_tools/building_map/doors/sliding_door.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,30 +6,32 @@ class SlidingDoor(Door):
def __init__(self, door_edge, level_elevation):
super().__init__(door_edge, level_elevation)

def generate(self, world_ele, options):
def generate(self, world_ele):
self.generate_sliding_section(
'right',
self.length - 0.01,
0,
(0.0, self.length),
options)
(0.0, self.length))

if not self.plugin == 'none':
plugin_ele = SubElement(self.model_ele, 'plugin')
plugin_ele.set('name', 'door')
plugin_ele.set('filename', 'libdoor.so')
plugin_ele.set('name', 'register_component')
plugin_ele.set('filename', 'libregister_component.so')
component_ele = SubElement(plugin_ele, 'component')
component_ele.set('name', 'Door')
plugin_params = {
'v_max_door': '0.2',
'a_max_door': '0.2',
'a_nom_door': '0.08',
'dx_min_door': '0.001',
'f_max_door': '100.0'
'f_max_door': '100.0',
'ros_interface': 'true'
}
for param_name, param_value in plugin_params.items():
ele = SubElement(plugin_ele, param_name)
ele = SubElement(component_ele, param_name)
ele.text = param_value

door_ele = SubElement(plugin_ele, 'door')
door_ele = SubElement(component_ele, 'door')
door_ele.set('name', self.name)
door_ele.set('type', 'SlidingDoor')
door_ele.set('left_joint_name', 'empty_joint')
Expand Down
18 changes: 10 additions & 8 deletions rmf_building_map_tools/building_map/doors/swing_door.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ def __init__(self, door_edge, level_elevation):
self.motion_radians = 3.14 * motion_degrees / 180.0
self.motion_direction = door_edge.params['motion_direction'].value

def generate(self, world_ele, options):
def generate(self, world_ele):
# This is configured to be negative by default to reflect how it is
# rendered on rmf_traffic_editor.
axis = 'z' if self.motion_direction < 0 else '-z'
Expand All @@ -20,25 +20,27 @@ def generate(self, world_ele, options):
0,
(0, self.motion_radians),
(self.length / 2, 0, 0),
axis,
options)
axis)

if not self.plugin == 'none':
plugin_ele = SubElement(self.model_ele, 'plugin')
plugin_ele.set('name', 'door')
plugin_ele.set('filename', 'libdoor.so')
plugin_ele.set('name', 'register_component')
plugin_ele.set('filename', 'libregister_component.so')
component_ele = SubElement(plugin_ele, 'component')
component_ele.set('name', 'Door')
plugin_params = {
'v_max_door': '0.5',
'a_max_door': '0.3',
'a_nom_door': '0.15',
'dx_min_door': '0.01',
'f_max_door': '500.0'
'f_max_door': '500.0',
'ros_interface': 'true'
}
for param_name, param_value in plugin_params.items():
ele = SubElement(plugin_ele, param_name)
ele = SubElement(component_ele, param_name)
ele.text = param_value

door_ele = SubElement(plugin_ele, 'door')
door_ele = SubElement(component_ele, 'door')
door_ele.set('name', self.name)
door_ele.set('type', 'SwingDoor')
door_ele.set('left_joint_name', 'empty_joint')
Expand Down
31 changes: 2 additions & 29 deletions rmf_building_map_tools/building_map/generator.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,7 @@ def generate_sdf(
self,
input_filename,
output_filename,
output_models_dir,
options
output_models_dir
):
print('generating {} from {}'.format(output_filename, input_filename))

Expand All @@ -41,40 +40,14 @@ def generate_sdf(
building.generate_sdf_models(output_models_dir)

# generate a top-level SDF for convenience
sdf = building.generate_sdf_world(options)
sdf = building.generate_sdf_world()

indent_etree(sdf)
sdf_str = str(ElementToString(sdf), 'utf-8')
with open(output_filename, 'w') as f:
f.write(sdf_str)
print(f'{len(sdf_str)} bytes written to {output_filename}')

def generate_gazebo_sdf(
self,
input_filename,
output_filename,
output_models_dir,
options
):
self.generate_sdf(
input_filename,
output_filename,
output_models_dir,
options + ['gazebo'])

def generate_ignition_sdf(
self,
input_filename,
output_filename,
output_models_dir,
options
):
self.generate_sdf(
input_filename,
output_filename,
output_models_dir,
options + ['ignition'])

def generate_nav(self, input_filename, output_dir):
building = self.parse_editor_yaml(input_filename)
nav_graphs = building.generate_nav_graphs()
Expand Down
8 changes: 4 additions & 4 deletions rmf_building_map_tools/building_map/level.py
Original file line number Diff line number Diff line change
Expand Up @@ -256,12 +256,12 @@ def generate_sdf_models(self, world_ele):
if 'spawn_robot_type' in vertex.params:
self.generate_robot_at_vertex_idx(vertex_idx, world_ele)

def generate_doors(self, world_ele, options):
def generate_doors(self, world_ele):
for door_edge in self.doors:
door_edge.calc_statistics(self.transformed_vertices)
self.generate_door(door_edge, world_ele, options)
self.generate_door(door_edge, world_ele)

def generate_door(self, door_edge, world_ele, options):
def generate_door(self, door_edge, world_ele):
door_name = door_edge.params['name'].value
door_type = door_edge.params['type'].value
print(f'generate door name={door_name} type={door_type}')
Expand All @@ -279,7 +279,7 @@ def generate_door(self, door_edge, world_ele, options):
print(f'door type {door_type} not yet implemented')

if door:
door.generate(world_ele, options)
door.generate(world_ele)

def generate_robot_at_vertex_idx(self, vertex_idx, world_ele):
vertex = self.transformed_vertices[vertex_idx]
Expand Down
Loading
Loading