Skip to content
Closed
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
54 changes: 37 additions & 17 deletions skrobot/model/robot_model.py
Original file line number Diff line number Diff line change
Expand Up @@ -1833,7 +1833,7 @@ def self_collision_check(self):
class RobotModel(CascadedLink):

def __init__(self, link_list=None, joint_list=None,
root_link=None):
root_link=None, urdf=None, include_mimic_joints=True):
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The __init__ method signature now includes new parameters urdf and include_mimic_joints but lacks documentation. Consider adding a docstring to document these parameters, especially since this is a public API method. The docstring should explain what urdf accepts (file path or URDF string), what include_mimic_joints does, and the defaults for all parameters.

Suggested change
root_link=None, urdf=None, include_mimic_joints=True):
root_link=None, urdf=None, include_mimic_joints=True):
"""Initialize a RobotModel instance.
Parameters
----------
link_list : sequence of Link, optional
Initial list of links to register in the model. If ``None``,
an empty list is used.
joint_list : sequence of Joint, optional
Initial list of joints to register in the model. If ``None``,
an empty list is used.
root_link : Link, optional
Root link of the robot model. If ``None``, a default or
inferred root link may be used depending on the implementation.
urdf : str, optional
URDF input used to build the robot model. This can be either a
file system path to a URDF file or a string containing URDF XML.
If ``None`` (the default), the model is not initialized from URDF.
include_mimic_joints : bool, optional
Whether to include mimic joints defined in the URDF when loading
the model. Defaults to ``True``.
"""

Copilot uses AI. Check for mistakes.
link_list = link_list or []
joint_list = joint_list or []
super(RobotModel, self).__init__(link_list, joint_list)
Expand All @@ -1853,6 +1853,39 @@ def __init__(self, link_list=None, joint_list=None,
self._relevance_predicate_table = \
self._compute_relevance_predicate_table()

if urdf is not None:
self._load_from_urdf(urdf, include_mimic_joints=include_mimic_joints)

def _load_from_urdf(self, urdf_input, include_mimic_joints=True):
"""Load URDF from a string or a file path.

Automatically detects if the input is a URDF string or a file path.

Parameters
----------
urdf_input : str
Either the URDF model description as a string, or the path to a
URDF file.
include_mimic_joints : bool, optional
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The docstring states that include_mimic_joints is "optional" but should specify the default value explicitly in the parameter description. Based on the function signature, the default is True, but this should be documented as "bool, optional (default: True)" for clarity.

Suggested change
include_mimic_joints : bool, optional
include_mimic_joints : bool, optional (default: True)

Copilot uses AI. Check for mistakes.
If True, mimic joints are included in the resulting
`RobotModel`'s `joint_list`.
"""
if os.path.isfile(urdf_input):
try:
with open(urdf_input, 'r') as f:
self.load_urdf_file(
file_obj=f, include_mimic_joints=include_mimic_joints)
except Exception as e:
logger.error(
"Failed to load URDF from file: %s. Error: %s",
urdf_input, e)
logger.error("Attempting to load as URDF string instead.")
self.load_urdf(
urdf_input, include_mimic_joints=include_mimic_joints)
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The fallback behavior in the exception handler is problematic. If a file path is provided and the file exists but loading fails (e.g., due to malformed XML), the code attempts to interpret the file path string as URDF content. This will likely fail in a confusing way since a file path is not valid URDF XML. Consider either removing the fallback entirely and re-raising the exception, or adding logic to check if the exception is due to file I/O vs parsing errors.

Suggested change
logger.error("Attempting to load as URDF string instead.")
self.load_urdf(
urdf_input, include_mimic_joints=include_mimic_joints)
# Do not attempt to interpret a file path as URDF XML content.
# Re-raise the original exception so callers see the real cause.
raise

Copilot uses AI. Check for mistakes.
else:
self.load_urdf(urdf_input,
include_mimic_joints=include_mimic_joints)

def reset_pose(self):
raise NotImplementedError()

Expand Down Expand Up @@ -2133,7 +2166,7 @@ def from_urdf(urdf_input, include_mimic_joints=True):

Parameters
----------
urdf_string : str
urdf_input : str
Either the URDF model description as a string, or the path to a
URDF file.
include_mimic_joints : bool, optional
Expand All @@ -2145,21 +2178,8 @@ def from_urdf(urdf_input, include_mimic_joints=True):
RobotModel
Robot model loaded from the URDF.
"""
robot_model = RobotModel()
if os.path.isfile(urdf_input):
try:
with open(urdf_input, 'r') as f:
robot_model.load_urdf_file(
file_obj=f, include_mimic_joints=include_mimic_joints)
except Exception as e:
logger.error("Failed to load URDF from file: %s. Error: %s", urdf_input, e)
logger.error("Attempting to load as URDF string instead.")
robot_model.load_urdf(
urdf_input, include_mimic_joints=include_mimic_joints)
else:
robot_model.load_urdf(urdf_input,
include_mimic_joints=include_mimic_joints)
return robot_model
return RobotModel(urdf=urdf_input,
include_mimic_joints=include_mimic_joints)

def load_urdf(self, urdf, include_mimic_joints=True):
is_python3 = sys.version_info.major > 2
Expand Down
18 changes: 9 additions & 9 deletions skrobot/models/fetch.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,27 +5,27 @@
from skrobot.data import fetch_urdfpath
from skrobot.model import RobotModel

from .urdf import RobotModelFromURDF


class Fetch(RobotModelFromURDF):
class Fetch(RobotModel):
"""Fetch Robot Model.
http://docs.fetchrobotics.com/robot_hardware.html
"""

def __init__(self, *args, **kwargs):
super(Fetch, self).__init__(*args, **kwargs)
def __init__(self, urdf=None, urdf_file=None):
# For backward compatibility, support both urdf and urdf_file
if urdf is not None and urdf_file is not None:
raise ValueError(
"'urdf' and 'urdf_file' cannot be given at the same time"
)
urdf_input = urdf or urdf_file or fetch_urdfpath()
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The use of or chaining to select the URDF input could cause unexpected behavior if an empty string is intentionally passed as urdf or urdf_file. The empty string is falsy in Python, so urdf or urdf_file or fetch_urdfpath() would skip over an empty string input and fall through to the default path. Consider using explicit None checks instead: urdf if urdf is not None else (urdf_file if urdf_file is not None else fetch_urdfpath()).

Suggested change
urdf_input = urdf or urdf_file or fetch_urdfpath()
if urdf is not None:
urdf_input = urdf
elif urdf_file is not None:
urdf_input = urdf_file
else:
urdf_input = fetch_urdfpath()

Copilot uses AI. Check for mistakes.
super(Fetch, self).__init__(urdf=urdf_input)
Comment on lines 15 to 27
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The new urdf and urdf_file parameters added to the Fetch.__init__ method lack test coverage. Consider adding tests to verify that custom URDF inputs can be provided and that the parameter validation works correctly (e.g., testing that providing both parameters raises a ValueError).

Copilot uses AI. Check for mistakes.
self.rarm_end_coords = CascadedCoords(parent=self.gripper_link,
name='rarm_end_coords')
self.rarm_end_coords.translate([0, 0, 0])
self.rarm_end_coords.rotate(0, axis='z')
self.end_coords = [self.rarm_end_coords]

@cached_property
def default_urdf_path(self):
return fetch_urdfpath()

def reset_pose(self):
self.torso_lift_joint.joint_angle(0)
self.shoulder_pan_joint.joint_angle(np.deg2rad(75.6304))
Expand Down
18 changes: 9 additions & 9 deletions skrobot/models/kuka.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,18 @@
from skrobot.data import kuka_urdfpath
from skrobot.model import RobotModel

from .urdf import RobotModelFromURDF


class Kuka(RobotModelFromURDF):
class Kuka(RobotModel):
"""Kuka Robot Model."""

def __init__(self, *args, **kwargs):
super(Kuka, self).__init__(*args, **kwargs)
def __init__(self, urdf=None, urdf_file=None):
# For backward compatibility, support both urdf and urdf_file
if urdf is not None and urdf_file is not None:
raise ValueError(
"'urdf' and 'urdf_file' cannot be given at the same time"
)
urdf_input = urdf or urdf_file or kuka_urdfpath()
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The use of or chaining to select the URDF input could cause unexpected behavior if an empty string is intentionally passed as urdf or urdf_file. The empty string is falsy in Python, so urdf or urdf_file or kuka_urdfpath() would skip over an empty string input and fall through to the default path. Consider using explicit None checks instead: urdf if urdf is not None else (urdf_file if urdf_file is not None else kuka_urdfpath()).

Suggested change
urdf_input = urdf or urdf_file or kuka_urdfpath()
urdf_input = (
urdf
if urdf is not None
else (urdf_file if urdf_file is not None else kuka_urdfpath())
)

Copilot uses AI. Check for mistakes.
super(Kuka, self).__init__(urdf=urdf_input)
Comment on lines 12 to 24
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The new urdf and urdf_file parameters added to the Kuka.__init__ method lack test coverage. Consider adding tests to verify that custom URDF inputs can be provided and that the parameter validation works correctly (e.g., testing that providing both parameters raises a ValueError).

Copilot uses AI. Check for mistakes.
self.rarm_end_coords = CascadedCoords(
parent=self.lbr_iiwa_with_wsg50__lbr_iiwa_link_7,
name='rarm_end_coords')
Expand All @@ -22,10 +26,6 @@ def __init__(self, *args, **kwargs):
self.rarm_end_coords.rotate(- np.pi / 2.0, axis='x')
self.end_coords = [self.rarm_end_coords]

@cached_property
def default_urdf_path(self):
return kuka_urdfpath()

def reset_manip_pose(self):
return self.angle_vector([0, np.deg2rad(10), 0,
np.deg2rad(-90), 0, np.deg2rad(90),
Expand Down
17 changes: 9 additions & 8 deletions skrobot/models/nextage.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,9 @@
from ..coordinates import CascadedCoords
from ..data import nextage_urdfpath
from ..model import RobotModel
from .urdf import RobotModelFromURDF


class Nextage(RobotModelFromURDF):
class Nextage(RobotModel):
"""
- Nextage Open Official Information.

Expand All @@ -18,8 +17,14 @@ class Nextage(RobotModelFromURDF):
https://github.com/tork-a/rtmros_nextage/tree/indigo-devel/nextage_description/urdf
"""

def __init__(self, *args, **kwargs):
super(Nextage, self).__init__(*args, **kwargs)
def __init__(self, urdf=None, urdf_file=None):
# For backward compatibility, support both urdf and urdf_file
if urdf is not None and urdf_file is not None:
raise ValueError(
"'urdf' and 'urdf_file' cannot be given at the same time"
)
urdf_input = urdf or urdf_file or nextage_urdfpath()
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The use of or chaining to select the URDF input could cause unexpected behavior if an empty string is intentionally passed as urdf or urdf_file. The empty string is falsy in Python, so urdf or urdf_file or nextage_urdfpath() would skip over an empty string input and fall through to the default path. Consider using explicit None checks instead: urdf if urdf is not None else (urdf_file if urdf_file is not None else nextage_urdfpath()).

Suggested change
urdf_input = urdf or urdf_file or nextage_urdfpath()
if urdf is not None:
urdf_input = urdf
elif urdf_file is not None:
urdf_input = urdf_file
else:
urdf_input = nextage_urdfpath()

Copilot uses AI. Check for mistakes.
super(Nextage, self).__init__(urdf=urdf_input)
Comment on lines 20 to 32
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The new urdf and urdf_file parameters added to the Nextage.__init__ method lack test coverage. Consider adding tests to verify that custom URDF inputs can be provided and that the parameter validation works correctly (e.g., testing that providing both parameters raises a ValueError).

Copilot uses AI. Check for mistakes.

# End effector coordinates
self.rarm_end_coords = CascadedCoords(
Expand All @@ -42,10 +47,6 @@ def __init__(self, *args, **kwargs):

self.reset_pose()

@cached_property
def default_urdf_path(self):
return nextage_urdfpath()

def reset_pose(self):
angle_vector = [
0.0,
Expand Down
17 changes: 9 additions & 8 deletions skrobot/models/panda.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,23 @@
from ..coordinates import CascadedCoords
from ..data import panda_urdfpath
from ..model import RobotModel
from .urdf import RobotModelFromURDF


class Panda(RobotModelFromURDF):
class Panda(RobotModel):

"""Panda Robot Model.

https://frankaemika.github.io/docs/control_parameters.html
"""

def __init__(self, *args, **kwargs):
super(Panda, self).__init__(*args, **kwargs)
def __init__(self, urdf=None, urdf_file=None):
# For backward compatibility, support both urdf and urdf_file
if urdf is not None and urdf_file is not None:
raise ValueError(
"'urdf' and 'urdf_file' cannot be given at the same time"
)
urdf_input = urdf or urdf_file or panda_urdfpath()
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The use of or chaining to select the URDF input could cause unexpected behavior if an empty string is intentionally passed as urdf or urdf_file. The empty string is falsy in Python, so urdf or urdf_file or panda_urdfpath() would skip over an empty string input and fall through to the default path. Consider using explicit None checks instead: urdf if urdf is not None else (urdf_file if urdf_file is not None else panda_urdfpath()).

Suggested change
urdf_input = urdf or urdf_file or panda_urdfpath()
urdf_input = (
urdf
if urdf is not None
else (urdf_file if urdf_file is not None else panda_urdfpath())
)

Copilot uses AI. Check for mistakes.
super(Panda, self).__init__(urdf=urdf_input)
Comment on lines 16 to 28
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The new urdf and urdf_file parameters added to the Panda.__init__ method lack test coverage. Consider adding tests to verify that custom URDF inputs can be provided and that the parameter validation works correctly (e.g., testing that providing both parameters raises a ValueError).

Copilot uses AI. Check for mistakes.

# End effector coordinate frame
# Based on franka_ros configuration:
Expand All @@ -27,10 +32,6 @@ def __init__(self, *args, **kwargs):
self.rarm_end_coords.rotate(np.deg2rad(-90), 'y')
self.reset_pose()

@cached_property
def default_urdf_path(self):
return panda_urdfpath()

def reset_pose(self):
angle_vector = [
0.03942226991057396,
Expand Down
18 changes: 9 additions & 9 deletions skrobot/models/pr2.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,17 +5,21 @@
from skrobot.data import pr2_urdfpath
from skrobot.model import RobotModel

from .urdf import RobotModelFromURDF


class PR2(RobotModelFromURDF):
class PR2(RobotModel):

"""PR2 Robot Model.

"""

def __init__(self, use_tight_joint_limit=True):
super(PR2, self).__init__()
def __init__(self, urdf=None, urdf_file=None, use_tight_joint_limit=True):
# For backward compatibility, support both urdf and urdf_file
if urdf is not None and urdf_file is not None:
raise ValueError(
"'urdf' and 'urdf_file' cannot be given at the same time"
)
urdf_input = urdf or urdf_file or pr2_urdfpath()
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The use of or chaining to select the URDF input could cause unexpected behavior if an empty string is intentionally passed as urdf or urdf_file. The empty string is falsy in Python, so urdf or urdf_file or pr2_urdfpath() would skip over an empty string input and fall through to the default path. Consider using explicit None checks instead: urdf if urdf is not None else (urdf_file if urdf_file is not None else pr2_urdfpath()).

Suggested change
urdf_input = urdf or urdf_file or pr2_urdfpath()
urdf_input = (
urdf
if urdf is not None
else (urdf_file if urdf_file is not None else pr2_urdfpath())
)

Copilot uses AI. Check for mistakes.
super(PR2, self).__init__(urdf=urdf_input)
Comment on lines 15 to 27
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The PR2 class still retains the default_urdf_path property (defined later in the file), while other robot models (Panda, Fetch, Kuka, Nextage) had this property removed in the refactoring. For consistency, the default_urdf_path property should be removed from PR2 as well, since the URDF path is now handled through the constructor parameters.

Copilot uses AI. Check for mistakes.

self.rarm_end_coords = CascadedCoords(
parent=self.r_gripper_tool_frame,
Expand Down Expand Up @@ -71,10 +75,6 @@ def __init__(self, use_tight_joint_limit=True):
j.min_angle = min_angle
j.max_angle = max_angle

@cached_property
def default_urdf_path(self):
return pr2_urdfpath()

@cached_property
def rarm(self):
rarm_links = [
Expand Down
21 changes: 12 additions & 9 deletions skrobot/models/r8_6.py
Original file line number Diff line number Diff line change
@@ -1,19 +1,22 @@
import os.path as osp

import skrobot
from skrobot.coordinates import CascadedCoords
from skrobot.data import r8_6_urdfpath


class R8_6(skrobot.model.RobotModel):

def __init__(self, urdf_path=None, *args, **kwargs):
super(R8_6, self).__init__(*args, **kwargs)
urdf_path = r8_6_urdfpath() if urdf_path is None else urdf_path
if osp.exists(urdf_path):
self.load_urdf_file(open(urdf_path, 'r'))
else:
raise ValueError()
def __init__(self, urdf=None, urdf_file=None, urdf_path=None):
# For backward compatibility, support urdf, urdf_file, and urdf_path
# urdf_path is treated as an alias for urdf_file for backward compatibility
specified_sources = [
src for src in (urdf, urdf_file, urdf_path) if src is not None
]
if len(specified_sources) > 1:
raise ValueError(
"Only one of 'urdf', 'urdf_file', or 'urdf_path' can be specified"
)
urdf_input = urdf or urdf_file or urdf_path or r8_6_urdfpath()
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The use of or chaining to select the URDF input could cause unexpected behavior if an empty string is intentionally passed. The empty string is falsy in Python, so this expression would skip over an empty string input and fall through to the next option or default path. Consider using explicit None checks instead: urdf if urdf is not None else (urdf_file if urdf_file is not None else (urdf_path if urdf_path is not None else r8_6_urdfpath())).

Suggested change
urdf_input = urdf or urdf_file or urdf_path or r8_6_urdfpath()
if urdf is not None:
urdf_input = urdf
elif urdf_file is not None:
urdf_input = urdf_file
elif urdf_path is not None:
urdf_input = urdf_path
else:
urdf_input = r8_6_urdfpath()

Copilot uses AI. Check for mistakes.
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The R8_6 class accepts three different parameter names (urdf, urdf_file, urdf_path) while other robot models (Panda, Fetch, Kuka, PR2, Nextage) only accept two (urdf, urdf_file). This inconsistency in the API design could confuse users. Consider whether urdf_path is necessary for backward compatibility or if it should be standardized across all models.

Copilot uses AI. Check for mistakes.
super(R8_6, self).__init__(urdf=urdf_input)
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The new urdf, urdf_file, and urdf_path parameters added to the R8_6.__init__ method lack test coverage. Consider adding tests to verify that custom URDF inputs can be provided, that the parameter validation works correctly (e.g., testing that providing multiple parameters raises a ValueError), and that backward compatibility with the urdf_path parameter is maintained.

Copilot uses AI. Check for mistakes.

# Define end effector coordinates for left arm
self.larm_end_coords = CascadedCoords(
Expand Down
29 changes: 21 additions & 8 deletions skrobot/models/urdf.py
Original file line number Diff line number Diff line change
@@ -1,21 +1,34 @@
import warnings

from ..model import RobotModel


class RobotModelFromURDF(RobotModel):
"""Deprecated: Use RobotModel with urdf parameter instead.
def __init__(self, urdf=None, urdf_file=None):
super(RobotModelFromURDF, self).__init__()
This class is kept for backward compatibility.
Use ``RobotModel(urdf=urdf_input)`` or ``RobotModel.from_urdf(urdf_input)``
instead.
"""

if urdf and urdf_file:
def __init__(self, urdf=None, urdf_file=None):
warnings.warn(
"RobotModelFromURDF is deprecated. "
"Use RobotModel(urdf=...) or RobotModel.from_urdf(...) instead.",
DeprecationWarning,
stacklevel=2
)
if urdf is not None and urdf_file is not None:
raise ValueError(
"'urdf' and 'urdf_file' cannot be given at the same time"
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The parameter checking logic uses urdf is not None and urdf_file is not None which correctly checks for both parameters being explicitly provided. However, the error message could be more helpful by indicating which parameters were actually provided.

Suggested change
"'urdf' and 'urdf_file' cannot be given at the same time"
"'urdf' and 'urdf_file' cannot be given at the same time; "
"received both 'urdf' and 'urdf_file' arguments."

Copilot uses AI. Check for mistakes.
)
if urdf:
self.load_urdf(urdf=urdf)
elif urdf_file:
self.load_urdf_file(file_obj=urdf_file)
if urdf is not None:
urdf_input = urdf
elif urdf_file is not None:
urdf_input = urdf_file
else:
self.load_urdf_file(file_obj=self.default_urdf_path)
urdf_input = self.default_urdf_path
Comment on lines +26 to +31
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The use of or chaining to select the URDF input could cause unexpected behavior if an empty string is intentionally passed. The empty string is falsy in Python, so this expression would skip over an empty string input and fall through to the next option or default path. Consider using explicit None checks with ternary operators to preserve the correct priority.

Copilot uses AI. Check for mistakes.
super(RobotModelFromURDF, self).__init__(urdf=urdf_input)
Comment on lines 14 to 32
Copy link

Copilot AI Jan 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The deprecation of RobotModelFromURDF lacks test coverage to verify that the DeprecationWarning is properly raised when the class is instantiated. Consider adding a test to ensure the deprecation warning is emitted and that the class still functions correctly for backward compatibility.

Copilot uses AI. Check for mistakes.

@property
def default_urdf_path(self):
Expand Down