Skip to content

Commit d017dbd

Browse files
committed
Address Copilot review comments
- Use explicit None checks instead of or-chaining for URDF input selection - Improve error message specificity in RobotModelFromURDF - Update docstring to explain auto-detection behavior (XML vs file path) - Add XML content detection (<?xml or <robot prefix) before file path check - Standardize R8_6 API to match other robots (remove urdf_path parameter) - Add test coverage for new URDF parameters and deprecation warning
1 parent 56b3e92 commit d017dbd

File tree

9 files changed

+125
-18
lines changed

9 files changed

+125
-18
lines changed

skrobot/model/robot_model.py

Lines changed: 19 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1847,9 +1847,13 @@ def __init__(self, link_list=None, joint_list=None,
18471847
root_link : Link, optional
18481848
Root link of the robot model.
18491849
urdf : str, optional
1850-
URDF input used to build the robot model. This can be either a
1851-
file system path to a URDF file or a string containing URDF XML.
1852-
If None (the default), the model is not initialized from URDF.
1850+
URDF input used to build the robot model. The value is interpreted
1851+
automatically: if the input looks like XML content (starts with
1852+
'<?xml' or '<robot'), it is treated as a string containing URDF
1853+
XML; otherwise, if ``os.path.isfile`` returns True, it is treated
1854+
as a file system path to a URDF file; otherwise it is treated as
1855+
URDF XML string. If None (the default), the model is not
1856+
initialized from URDF.
18531857
include_mimic_joints : bool, optional (default: True)
18541858
Whether to include mimic joints defined in the URDF when loading
18551859
the model.
@@ -1880,6 +1884,9 @@ def _load_from_urdf(self, urdf_input, include_mimic_joints=True):
18801884
"""Load URDF from a string or a file path.
18811885
18821886
Automatically detects if the input is a URDF string or a file path.
1887+
If the input looks like XML content (starts with '<?xml' or '<robot'),
1888+
it is treated as URDF XML string. Otherwise, if the input is an
1889+
existing file path, it is loaded as a file.
18831890
18841891
Parameters
18851892
----------
@@ -1890,6 +1897,15 @@ def _load_from_urdf(self, urdf_input, include_mimic_joints=True):
18901897
If True, mimic joints are included in the resulting
18911898
`RobotModel`'s `joint_list`.
18921899
"""
1900+
# First, check if the input looks like URDF/XML content
1901+
if isinstance(urdf_input, str):
1902+
stripped = urdf_input.lstrip()
1903+
if stripped.startswith('<?xml') or stripped.startswith('<robot'):
1904+
self.load_urdf(
1905+
urdf_input, include_mimic_joints=include_mimic_joints)
1906+
return
1907+
1908+
# If it doesn't look like XML, check if it's a file path
18931909
if os.path.isfile(urdf_input):
18941910
with open(urdf_input, 'r') as f:
18951911
self.load_urdf_file(

skrobot/models/fetch.py

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,12 @@ def __init__(self, urdf=None, urdf_file=None):
1818
raise ValueError(
1919
"'urdf' and 'urdf_file' cannot be given at the same time"
2020
)
21-
urdf_input = urdf or urdf_file or fetch_urdfpath()
21+
if urdf is not None:
22+
urdf_input = urdf
23+
elif urdf_file is not None:
24+
urdf_input = urdf_file
25+
else:
26+
urdf_input = fetch_urdfpath()
2227
super(Fetch, self).__init__(urdf=urdf_input)
2328
self.rarm_end_coords = CascadedCoords(parent=self.gripper_link,
2429
name='rarm_end_coords')

skrobot/models/kuka.py

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,12 @@ def __init__(self, urdf=None, urdf_file=None):
1515
raise ValueError(
1616
"'urdf' and 'urdf_file' cannot be given at the same time"
1717
)
18-
urdf_input = urdf or urdf_file or kuka_urdfpath()
18+
if urdf is not None:
19+
urdf_input = urdf
20+
elif urdf_file is not None:
21+
urdf_input = urdf_file
22+
else:
23+
urdf_input = kuka_urdfpath()
1924
super(Kuka, self).__init__(urdf=urdf_input)
2025
self.rarm_end_coords = CascadedCoords(
2126
parent=self.lbr_iiwa_with_wsg50__lbr_iiwa_link_7,

skrobot/models/nextage.py

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,12 @@ def __init__(self, urdf=None, urdf_file=None):
2323
raise ValueError(
2424
"'urdf' and 'urdf_file' cannot be given at the same time"
2525
)
26-
urdf_input = urdf or urdf_file or nextage_urdfpath()
26+
if urdf is not None:
27+
urdf_input = urdf
28+
elif urdf_file is not None:
29+
urdf_input = urdf_file
30+
else:
31+
urdf_input = nextage_urdfpath()
2732
super(Nextage, self).__init__(urdf=urdf_input)
2833

2934
# End effector coordinates

skrobot/models/panda.py

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,12 @@ def __init__(self, urdf=None, urdf_file=None):
1919
raise ValueError(
2020
"'urdf' and 'urdf_file' cannot be given at the same time"
2121
)
22-
urdf_input = urdf or urdf_file or panda_urdfpath()
22+
if urdf is not None:
23+
urdf_input = urdf
24+
elif urdf_file is not None:
25+
urdf_input = urdf_file
26+
else:
27+
urdf_input = panda_urdfpath()
2328
super(Panda, self).__init__(urdf=urdf_input)
2429

2530
# End effector coordinate frame

skrobot/models/pr2.py

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,12 @@ def __init__(self, urdf=None, urdf_file=None, use_tight_joint_limit=True):
1818
raise ValueError(
1919
"'urdf' and 'urdf_file' cannot be given at the same time"
2020
)
21-
urdf_input = urdf or urdf_file or pr2_urdfpath()
21+
if urdf is not None:
22+
urdf_input = urdf
23+
elif urdf_file is not None:
24+
urdf_input = urdf_file
25+
else:
26+
urdf_input = pr2_urdfpath()
2227
super(PR2, self).__init__(urdf=urdf_input)
2328

2429
self.rarm_end_coords = CascadedCoords(

skrobot/models/r8_6.py

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -5,17 +5,18 @@
55

66
class R8_6(skrobot.model.RobotModel):
77

8-
def __init__(self, urdf=None, urdf_file=None, urdf_path=None):
9-
# For backward compatibility, support urdf, urdf_file, and urdf_path
10-
# urdf_path is treated as an alias for urdf_file for backward compatibility
11-
specified_sources = [
12-
src for src in (urdf, urdf_file, urdf_path) if src is not None
13-
]
14-
if len(specified_sources) > 1:
8+
def __init__(self, urdf=None, urdf_file=None):
9+
# For backward compatibility, support both urdf and urdf_file
10+
if urdf is not None and urdf_file is not None:
1511
raise ValueError(
16-
"Only one of 'urdf', 'urdf_file', or 'urdf_path' can be specified"
12+
"'urdf' and 'urdf_file' cannot be given at the same time"
1713
)
18-
urdf_input = urdf or urdf_file or urdf_path or r8_6_urdfpath()
14+
if urdf is not None:
15+
urdf_input = urdf
16+
elif urdf_file is not None:
17+
urdf_input = urdf_file
18+
else:
19+
urdf_input = r8_6_urdfpath()
1920
super(R8_6, self).__init__(urdf=urdf_input)
2021

2122
# Define end effector coordinates for left arm

skrobot/models/urdf.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,8 @@ def __init__(self, urdf=None, urdf_file=None):
2020
)
2121
if urdf is not None and urdf_file is not None:
2222
raise ValueError(
23-
"'urdf' and 'urdf_file' cannot be given at the same time"
23+
"'urdf' and 'urdf_file' cannot be given at the same time; "
24+
"received both 'urdf' and 'urdf_file' arguments."
2425
)
2526
if urdf is not None:
2627
urdf_input = urdf

tests/skrobot_tests/test_urdf.py

Lines changed: 64 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,13 @@
11
import os
22
import sys
33
import unittest
4+
import warnings
45

56
from skrobot.data import fetch_urdfpath
7+
from skrobot.data import panda_urdfpath
8+
from skrobot.model import RobotModel
9+
from skrobot.models import Fetch
10+
from skrobot.models import Panda
611
from skrobot.models.urdf import RobotModelFromURDF
712
from skrobot.utils.urdf import mesh_simplify_factor
813

@@ -32,3 +37,62 @@ def test_load_urdfmodel_with_simplification(self):
3237
# load using existing cache
3338
with mesh_simplify_factor(0.1):
3439
RobotModelFromURDF(urdf_file=fetch_urdfpath())
40+
41+
42+
class TestRobotModelFromURDFDeprecation(unittest.TestCase):
43+
44+
def test_deprecation_warning(self):
45+
"""Test that RobotModelFromURDF raises DeprecationWarning."""
46+
with warnings.catch_warnings(record=True) as w:
47+
warnings.simplefilter("always")
48+
RobotModelFromURDF(urdf_file=panda_urdfpath())
49+
self.assertEqual(len(w), 1)
50+
self.assertTrue(issubclass(w[0].category, DeprecationWarning))
51+
self.assertIn("deprecated", str(w[0].message).lower())
52+
53+
54+
class TestRobotModelURDFParameters(unittest.TestCase):
55+
56+
def test_robot_model_with_urdf_file_path(self):
57+
"""Test RobotModel initialization with urdf file path."""
58+
robot = RobotModel(urdf=panda_urdfpath())
59+
self.assertEqual(robot.name, "panda")
60+
61+
def test_robot_model_with_urdf_string(self):
62+
"""Test RobotModel initialization with urdf string."""
63+
with open(panda_urdfpath(), 'r') as f:
64+
urdf_string = f.read()
65+
robot = RobotModel(urdf=urdf_string)
66+
self.assertEqual(robot.name, "panda")
67+
68+
def test_robot_model_from_urdf_static_method(self):
69+
"""Test RobotModel.from_urdf static method."""
70+
robot = RobotModel.from_urdf(panda_urdfpath())
71+
self.assertEqual(robot.name, "panda")
72+
73+
def test_panda_with_custom_urdf(self):
74+
"""Test Panda with custom urdf parameter."""
75+
panda = Panda(urdf=panda_urdfpath())
76+
self.assertEqual(panda.name, "panda")
77+
78+
def test_panda_with_custom_urdf_file(self):
79+
"""Test Panda with custom urdf_file parameter."""
80+
panda = Panda(urdf_file=panda_urdfpath())
81+
self.assertEqual(panda.name, "panda")
82+
83+
def test_fetch_with_custom_urdf(self):
84+
"""Test Fetch with custom urdf parameter."""
85+
fetch = Fetch(urdf=fetch_urdfpath())
86+
self.assertEqual(fetch.name, "fetch")
87+
88+
def test_panda_raises_error_with_both_urdf_params(self):
89+
"""Test that providing both urdf and urdf_file raises ValueError."""
90+
with self.assertRaises(ValueError) as context:
91+
Panda(urdf="test", urdf_file="test2")
92+
self.assertIn("cannot be given at the same time", str(context.exception))
93+
94+
def test_fetch_raises_error_with_both_urdf_params(self):
95+
"""Test that providing both urdf and urdf_file raises ValueError."""
96+
with self.assertRaises(ValueError) as context:
97+
Fetch(urdf="test", urdf_file="test2")
98+
self.assertIn("cannot be given at the same time", str(context.exception))

0 commit comments

Comments
 (0)