Skip to content

Commit 98c373f

Browse files
authored
Add support for separate collision mesh format in convert-urdf-mesh (#593)
This change allows different mesh formats for visual and collision geometries in URDF files. Collision meshes now default to STL format for better compatibility with physics engines, while visual meshes remain as DAE to preserve colors and textures. Key changes: - Add --collision-mesh-format option (default: stl) - Implement context tracking to distinguish visual/collision meshes - Update mesh conversion logic to handle formats independently
1 parent 9d13fc3 commit 98c373f

File tree

2 files changed

+46
-21
lines changed

2 files changed

+46
-21
lines changed

skrobot/apps/convert_urdf_mesh.py

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,11 @@ def main():
2828
parser.add_argument('--format', '-f',
2929
default='dae',
3030
choices=['dae', 'stl'],
31-
help='Mesh format for export. Default is dae.')
31+
help='Mesh format for visual mesh export. Default is dae.')
32+
parser.add_argument('--collision-mesh-format',
33+
default='stl',
34+
choices=['dae', 'stl'],
35+
help='Mesh format for collision mesh export. Default is stl.')
3236
parser.add_argument('--output', '-o', help='Path for the output URDF file. If not specified, a filename is automatically generated based on the input URDF file.') # NOQA
3337
parser.add_argument('--inplace', '-i', action='store_true',
3438
help='Modify the input URDF file inplace. If not specified, a new file is created.') # NOQA
@@ -133,7 +137,8 @@ def nullcontext(enter_result=None):
133137
decimation_area_ratio_threshold=args.decimation_area_ratio_threshold, # NOQA
134138
simplify_vertex_clustering_voxel_size=args.voxel_size,
135139
target_triangles=args.target_triangles,
136-
overwrite_mesh=args.overwrite_mesh), apply_scale(args.scale):
140+
overwrite_mesh=args.overwrite_mesh,
141+
collision_mesh_format='.' + args.collision_mesh_format), apply_scale(args.scale):
137142
print(f"Saving new URDF to: {output_path}")
138143
# Ensure output directory exists
139144
output_dir = output_path.parent

skrobot/utils/urdf.py

Lines changed: 39 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -43,13 +43,15 @@
4343
_CONFIGURABLE_VALUES = {"mesh_simplify_factor": np.inf,
4444
'no_mesh_load_mode': False,
4545
'export_mesh_format': None,
46+
'collision_mesh_format': None,
4647
'decimation_area_ratio_threshold': None,
4748
'simplify_vertex_clustering_voxel_size': None,
4849
'target_triangles': None,
4950
'enable_mesh_cache': False,
5051
'force_visual_mesh_origin_to_zero': False,
5152
'overwrite_mesh': False,
5253
'scale_factor': 1.0,
54+
'_current_geometry_context': None, # 'collision' or 'visual'
5355
}
5456
_MESH_CACHE = {}
5557

@@ -74,8 +76,10 @@ def export_mesh_format(
7476
decimation_area_ratio_threshold=None,
7577
simplify_vertex_clustering_voxel_size=None,
7678
target_triangles=None,
77-
overwrite_mesh=False):
79+
overwrite_mesh=False,
80+
collision_mesh_format=None):
7881
_CONFIGURABLE_VALUES["export_mesh_format"] = mesh_format
82+
_CONFIGURABLE_VALUES["collision_mesh_format"] = collision_mesh_format
7983
_CONFIGURABLE_VALUES["decimation_area_ratio_threshold"] = \
8084
decimation_area_ratio_threshold
8185
_CONFIGURABLE_VALUES["simplify_vertex_clustering_voxel_size"] = \
@@ -84,6 +88,7 @@ def export_mesh_format(
8488
_CONFIGURABLE_VALUES["overwrite_mesh"] = overwrite_mesh
8589
yield
8690
_CONFIGURABLE_VALUES["export_mesh_format"] = None
91+
_CONFIGURABLE_VALUES["collision_mesh_format"] = None
8792
_CONFIGURABLE_VALUES["decimation_area_ratio_threshold"] = None
8893
_CONFIGURABLE_VALUES["simplify_vertex_clustering_voxel_size"] = None
8994
_CONFIGURABLE_VALUES["target_triangles"] = None
@@ -1009,11 +1014,16 @@ def _to_xml(self, parent, path):
10091014

10101015
return node
10111016

1012-
ext = _CONFIGURABLE_VALUES['export_mesh_format']
1017+
# Determine which format to use based on context
1018+
is_collision = (_CONFIGURABLE_VALUES.get('_current_geometry_context')
1019+
== 'collision')
1020+
ext = (_CONFIGURABLE_VALUES['collision_mesh_format'] if is_collision
1021+
else _CONFIGURABLE_VALUES['export_mesh_format'])
1022+
10131023
if ext is not None:
10141024
if not fn.endswith(ext):
10151025
name, _ = os.path.splitext(fn)
1016-
fn = name + _CONFIGURABLE_VALUES['export_mesh_format']
1026+
fn = name + ext
10171027
self.filename = os.path.splitext(self.filename)[0] + ext
10181028
if os.path.exists(fn):
10191029
# skip mesh save process but still apply scaling
@@ -1481,16 +1491,21 @@ def _from_xml(cls, node, path):
14811491
return Collision(**kwargs)
14821492

14831493
def _to_xml(self, parent, path):
1484-
node = self._unparse(path)
1494+
# Set context for mesh conversion
1495+
_CONFIGURABLE_VALUES['_current_geometry_context'] = 'collision'
1496+
try:
1497+
node = self._unparse(path)
14851498

1486-
# Apply scale factor to collision origin
1487-
scaled_origin = self.origin.copy()
1488-
scale_factor = _CONFIGURABLE_VALUES.get('scale_factor', 1.0)
1489-
if scale_factor != 1.0:
1490-
scaled_origin[:3, 3] *= scale_factor
1499+
# Apply scale factor to collision origin
1500+
scaled_origin = self.origin.copy()
1501+
scale_factor = _CONFIGURABLE_VALUES.get('scale_factor', 1.0)
1502+
if scale_factor != 1.0:
1503+
scaled_origin[:3, 3] *= scale_factor
14911504

1492-
node.append(unparse_origin(scaled_origin))
1493-
return node
1505+
node.append(unparse_origin(scaled_origin))
1506+
return node
1507+
finally:
1508+
_CONFIGURABLE_VALUES['_current_geometry_context'] = None
14941509

14951510

14961511
class Visual(URDFType):
@@ -1595,16 +1610,21 @@ def _from_xml(cls, node, path):
15951610
return Visual(**kwargs)
15961611

15971612
def _to_xml(self, parent, path):
1598-
node = self._unparse(path)
1613+
# Set context for mesh conversion
1614+
_CONFIGURABLE_VALUES['_current_geometry_context'] = 'visual'
1615+
try:
1616+
node = self._unparse(path)
15991617

1600-
# Apply scale factor to visual origin
1601-
scaled_origin = self.origin.copy()
1602-
scale_factor = _CONFIGURABLE_VALUES.get('scale_factor', 1.0)
1603-
if scale_factor != 1.0:
1604-
scaled_origin[:3, 3] *= scale_factor
1618+
# Apply scale factor to visual origin
1619+
scaled_origin = self.origin.copy()
1620+
scale_factor = _CONFIGURABLE_VALUES.get('scale_factor', 1.0)
1621+
if scale_factor != 1.0:
1622+
scaled_origin[:3, 3] *= scale_factor
16051623

1606-
node.append(unparse_origin(scaled_origin))
1607-
return node
1624+
node.append(unparse_origin(scaled_origin))
1625+
return node
1626+
finally:
1627+
_CONFIGURABLE_VALUES['_current_geometry_context'] = None
16081628

16091629

16101630
class Inertial(URDFType):

0 commit comments

Comments
 (0)