Skip to content
Closed
Show file tree
Hide file tree
Changes from all 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
82 changes: 65 additions & 17 deletions skrobot/model/robot_model.py
Original file line number Diff line number Diff line change
Expand Up @@ -1833,7 +1833,31 @@ 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.
"""Initialize a RobotModel instance.

Parameters
----------
link_list : list of Link, optional
Initial list of links to register in the model.
If None, an empty list is used.
joint_list : list 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.
urdf : str, optional
URDF input used to build the robot model. The value is interpreted
automatically: if the input looks like XML content (starts with
'<?xml' or '<robot'), it is treated as a string containing URDF
XML; otherwise, if ``os.path.isfile`` returns True, it is treated
as a file system path to a URDF file; otherwise it is treated as
URDF XML string. If None (the default), the model is not
initialized from URDF.
include_mimic_joints : bool, optional (default: True)
Whether to include mimic joints defined in the URDF when loading
the model.
"""
link_list = link_list or []
joint_list = joint_list or []
super(RobotModel, self).__init__(link_list, joint_list)
Expand All @@ -1853,6 +1877,43 @@ 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.
If the input looks like XML content (starts with '<?xml' or '<robot'),
it is treated as URDF XML string. Otherwise, if the input is an
existing file path, it is loaded as a file.

Parameters
----------
urdf_input : str
Either the URDF model description as a string, or the path to a
URDF file.
include_mimic_joints : bool, optional (default: True)
If True, mimic joints are included in the resulting
`RobotModel`'s `joint_list`.
"""
# First, check if the input looks like URDF/XML content
if isinstance(urdf_input, str):
stripped = urdf_input.lstrip()
if stripped.startswith('<?xml') or stripped.startswith('<robot'):
self.load_urdf(
urdf_input, include_mimic_joints=include_mimic_joints)
return

# If it doesn't look like XML, check if it's a file path
if os.path.isfile(urdf_input):
with open(urdf_input, 'r') as f:
self.load_urdf_file(
file_obj=f, include_mimic_joints=include_mimic_joints)
else:
self.load_urdf(urdf_input,
include_mimic_joints=include_mimic_joints)
Comment on lines +1909 to +1915
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 _load_from_urdf method uses os.path.isfile() to detect whether the input is a file path or URDF string. This approach has a potential edge case: if a URDF XML string happens to start with a valid file path that exists on the system, it will be incorrectly treated as a file. Consider checking for XML content (e.g., starts with '<?xml' or '<robot') before falling back to file path detection.

Suggested change
if os.path.isfile(urdf_input):
with open(urdf_input, 'r') as f:
self.load_urdf_file(
file_obj=f, include_mimic_joints=include_mimic_joints)
else:
self.load_urdf(urdf_input,
include_mimic_joints=include_mimic_joints)
# First, check if the input looks like URDF/XML content.
if isinstance(urdf_input, six.string_types):
stripped = urdf_input.lstrip()
if stripped.startswith('<?xml') or stripped.startswith('<robot'):
self.load_urdf(
urdf_input, include_mimic_joints=include_mimic_joints
)
return
# If it doesn't look like XML, fall back to treating it as a file path
# when possible; otherwise, pass it to load_urdf as before.
if isinstance(urdf_input, six.string_types) and os.path.isfile(urdf_input):
with open(urdf_input, 'r') as f:
self.load_urdf_file(
file_obj=f, include_mimic_joints=include_mimic_joints
)
else:
self.load_urdf(
urdf_input, include_mimic_joints=include_mimic_joints
)

Copilot uses AI. Check for mistakes.
Comment on lines +1883 to +1915
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 _load_from_urdf method has incomplete input validation. If urdf_input is not a string (e.g., accidentally passed as a file object or other type), the code will skip the XML detection block (line 1901) and attempt to call os.path.isfile(urdf_input) on line 1909 with a non-string argument, which could cause a TypeError or unexpected behavior. Consider adding explicit type checking at the start of the method to provide a clearer error message if urdf_input is not a string.

Copilot uses AI. Check for mistakes.

def reset_pose(self):
raise NotImplementedError()

Expand Down Expand Up @@ -2133,7 +2194,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 +2206,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
23 changes: 14 additions & 9 deletions skrobot/models/fetch.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,27 +5,32 @@
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"
)
if urdf is not None:
urdf_input = urdf
elif urdf_file is not None:
urdf_input = urdf_file
else:
urdf_input = fetch_urdfpath()
super(Fetch, self).__init__(urdf=urdf_input)
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
23 changes: 14 additions & 9 deletions skrobot/models/kuka.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,23 @@
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"
)
if urdf is not None:
urdf_input = urdf
elif urdf_file is not None:
urdf_input = urdf_file
else:
urdf_input = kuka_urdfpath()
super(Kuka, self).__init__(urdf=urdf_input)
self.rarm_end_coords = CascadedCoords(
parent=self.lbr_iiwa_with_wsg50__lbr_iiwa_link_7,
name='rarm_end_coords')
Expand All @@ -22,10 +31,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
22 changes: 14 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,19 @@ 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"
)
if urdf is not None:
urdf_input = urdf
elif urdf_file is not None:
urdf_input = urdf_file
else:
urdf_input = nextage_urdfpath()
super(Nextage, self).__init__(urdf=urdf_input)

# End effector coordinates
self.rarm_end_coords = CascadedCoords(
Expand All @@ -42,10 +52,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
22 changes: 14 additions & 8 deletions skrobot/models/panda.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,28 @@
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"
)
if urdf is not None:
urdf_input = urdf
elif urdf_file is not None:
urdf_input = urdf_file
else:
urdf_input = panda_urdfpath()
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 parameter handling logic for urdf and urdf_file is duplicated across all robot model classes (Panda, Fetch, Kuka, PR2, Nextage, R8_6). Consider extracting this into a helper method in the base RobotModel class or creating a decorator to reduce code duplication. This would make maintenance easier and ensure consistency across all robot models.

Copilot uses AI. Check for mistakes.

# End effector coordinate frame
# Based on franka_ros configuration:
Expand All @@ -27,10 +37,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
23 changes: 14 additions & 9 deletions skrobot/models/pr2.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,17 +5,26 @@
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"
)
if urdf is not None:
urdf_input = urdf
elif urdf_file is not None:
urdf_input = urdf_file
else:
urdf_input = pr2_urdfpath()
super(PR2, self).__init__(urdf=urdf_input)

self.rarm_end_coords = CascadedCoords(
parent=self.r_gripper_tool_frame,
Expand Down Expand Up @@ -71,10 +80,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
20 changes: 12 additions & 8 deletions skrobot/models/r8_6.py
Original file line number Diff line number Diff line change
@@ -1,19 +1,23 @@
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'))
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"
)
if urdf is not None:
urdf_input = urdf
elif urdf_file is not None:
urdf_input = urdf_file
else:
raise ValueError()
urdf_input = r8_6_urdfpath()
super(R8_6, self).__init__(urdf=urdf_input)

# Define end effector coordinates for left arm
self.larm_end_coords = CascadedCoords(
Expand Down
Loading