Skip to content
Merged
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
10 changes: 5 additions & 5 deletions examples/batch_ik_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -91,19 +91,19 @@ def main():
# Initialize robot based on selection
if args.robot == 'fetch':
robot = Fetch()
arm = robot.rarm_with_torso if args.with_torso else robot.rarm
arm = robot.arm_with_torso if args.with_torso else robot.arm
elif args.robot == 'pr2':
robot = PR2()
arm = robot.rarm_with_torso if args.with_torso else robot.rarm
arm = robot.right_arm_with_torso if args.with_torso else robot.right_arm
elif args.robot == 'panda':
robot = Panda()
arm = robot.rarm
arm = robot.arm
elif args.robot == 'r8_6':
robot = R8_6()
arm = robot.rarm
arm = robot.right_arm
elif args.robot == 'nextage':
robot = Nextage()
arm = robot.rarm
arm = robot.right_arm

robot.reset_pose()

Expand Down
16 changes: 8 additions & 8 deletions examples/collision_free_trajectory.py
Original file line number Diff line number Diff line change
Expand Up @@ -79,13 +79,13 @@
set_robot_config(robot_model, joint_list, joint_angles)
target_coords = skrobot.coordinates.Coordinates([0.8, -0.6, 0.8], [0, 0, 0])

rarm_end_coords = skrobot.coordinates.CascadedCoords(
right_arm_end_coords = skrobot.coordinates.CascadedCoords(
parent=robot_model.r_gripper_tool_frame,
name='rarm_end_coords')
name='right_arm_end_coords')
robot_model.inverse_kinematics(
target_coords=target_coords,
link_list=link_list,
move_target=robot_model.rarm_end_coords, rotation_axis=True)
move_target=robot_model.right_arm_end_coords, rotation_axis=True)
av_goal = get_robot_config(robot_model, joint_list, with_base=with_base)

# collision checker setup
Expand Down Expand Up @@ -134,17 +134,17 @@

print("solving time : {0} sec".format(time.time() - ts))

rarm_point_history = []
arm_point_history = []
line_string = None
for av in av_seq:
set_robot_config(robot_model, joint_list, av, with_base=with_base)
rarm_point_history.append(rarm_end_coords.worldpos())
arm_point_history.append(right_arm_end_coords.worldpos())

# update rarm trajectory visualization
# update arm trajectory visualization
if line_string is not None:
viewer.delete(line_string)
if len(rarm_point_history) > 1:
line_string = LineString(np.array(rarm_point_history))
if len(arm_point_history) > 1:
line_string = LineString(np.array(arm_point_history))
viewer.add(line_string)

sscc.update_color()
Expand Down
16 changes: 8 additions & 8 deletions examples/grasp_and_pull_box.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,22 +25,22 @@ def init_pose():


def open_right_gripper():
robot_model.gripper_distance(0.093, arm='rarm')
robot_model.gripper_distance(0.093, arm='right_arm')
viewer.redraw()


def close_right_gripper():
robot_model.gripper_distance(0.0, arm='rarm')
robot_model.gripper_distance(0.0, arm='right_arm')
viewer.redraw()


def open_left_gripper():
robot_model.gripper_distance(0.093, arm='larm')
robot_model.gripper_distance(0.093, arm='left_arm')
viewer.redraw()


def close_left_gripper():
robot_model.gripper_distance(0.0, arm='larm')
robot_model.gripper_distance(0.0, arm='left_arm')
viewer.redraw()


Expand All @@ -66,7 +66,7 @@ def move_to_box(box):


def grasp_box(box):
robot_model.gripper_distance(0.036, arm='rarm')
robot_model.gripper_distance(0.036, arm='right_arm')
move_target.assoc(box)
viewer.redraw()

Expand Down Expand Up @@ -109,10 +109,10 @@ def pull_box(box):
robot_model.r_forearm_roll_link,
robot_model.r_wrist_flex_link,
robot_model.r_wrist_roll_link]
rarm_end_coords = skrobot.coordinates.CascadedCoords(
right_arm_end_coords = skrobot.coordinates.CascadedCoords(
parent=robot_model.r_gripper_tool_frame,
name='rarm_end_coords')
move_target = rarm_end_coords
name='right_arm_end_coords')
move_target = right_arm_end_coords

# Create viewer
if args.viewer == 'trimesh':
Expand Down
10 changes: 5 additions & 5 deletions examples/notebooks/colab_jupyter_viewer_demo.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -152,10 +152,10 @@
" robot.r_wrist_roll_link]\n",
"\n",
"# Create end-effector coordinates\n",
"rarm_end_coords = skrobot.coordinates.CascadedCoords(\n",
"right_arm_end_coords = skrobot.coordinates.CascadedCoords(\n",
" parent=robot.r_gripper_tool_frame,\n",
" name='rarm_end_coords')\n",
"move_target = rarm_end_coords\n",
" name='right_arm_end_coords')\n",
"move_target = right_arm_end_coords\n",
"\n",
"# Create viewer and add robot\n",
"grasp_viewer = skrobot.viewers.JupyterNotebookViewer(height=600)\n",
Expand Down Expand Up @@ -193,7 +193,7 @@
"robot.reset_pose()\n",
"target_coords = skrobot.coordinates.Coordinates([0.5, -0.3, 0.7], [0, 0, 0])\n",
"robot.inverse_kinematics(target_coords, link_list=link_list, move_target=move_target)\n",
"robot.gripper_distance(0.093, arm='rarm') # Open gripper\n",
"robot.gripper_distance(0.093, arm='right_arm') # Open gripper\n",
"grasp_viewer.redraw()\n",
"time.sleep(1)\n",
"\n",
Expand All @@ -213,7 +213,7 @@
"\n",
"# 3. Grasp box\n",
"print(\"3. Grasping box...\")\n",
"robot.gripper_distance(0.036, arm='rarm') # Close gripper\n",
"robot.gripper_distance(0.036, arm='right_arm') # Close gripper\n",
"move_target.assoc(box) # Attach box to gripper\n",
"grasp_viewer.redraw()\n",
"time.sleep(1)\n",
Expand Down
14 changes: 7 additions & 7 deletions examples/notebooks/jupyter_collision_free_with_base.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -108,13 +108,13 @@
"set_robot_config(robot_model, joint_list, joint_angles)\n",
"target_coords = skrobot.coordinates.Coordinates([0.8, -0.6, 0.8], [0, 0, 0])\n",
"\n",
"rarm_end_coords = skrobot.coordinates.CascadedCoords(\n",
"right_arm_end_coords = skrobot.coordinates.CascadedCoords(\n",
" parent=robot_model.r_gripper_tool_frame,\n",
" name='rarm_end_coords')\n",
" name='right_arm_end_coords')\n",
"robot_model.inverse_kinematics(\n",
" target_coords=target_coords,\n",
" link_list=link_list,\n",
" move_target=robot_model.rarm_end_coords, rotation_axis=True)\n",
" move_target=robot_model.right_arm_end_coords, rotation_axis=True)\n",
"av_goal = get_robot_config(robot_model, joint_list, with_base=True)\n",
"\n",
"print(f\"Goal config (7 joints + 3 base): {av_goal}\")\n",
Expand Down Expand Up @@ -214,19 +214,19 @@
"# Display viewer in THIS cell\n",
"viewer.show()\n",
"\n",
"rarm_point_history = []\n",
"arm_point_history = []\n",
"line_string = None\n",
"\n",
"for i, av in enumerate(av_seq):\n",
" # Update robot configuration (joints + base)\n",
" set_robot_config(robot_model, joint_list, av, with_base=True)\n",
" rarm_point_history.append(rarm_end_coords.worldpos())\n",
" arm_point_history.append(right_arm_end_coords.worldpos())\n",
"\n",
" # Update trajectory visualization\n",
" if line_string is not None:\n",
" viewer.delete(line_string)\n",
" if len(rarm_point_history) > 1:\n",
" line_string = LineString(np.array(rarm_point_history))\n",
" if len(arm_point_history) > 1:\n",
" line_string = LineString(np.array(arm_point_history))\n",
" viewer.add(line_string)\n",
"\n",
" # Update collision sphere colors\n",
Expand Down
20 changes: 10 additions & 10 deletions examples/pr2_inverse_kinematics.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@ def demonstrate_revert_if_fail(robot_model, target_coords, link_list, viewer,
print("=" * 60)

# Get the correct end-effector position after first IK
actual_end_pos = robot_model.rarm_end_coords.worldpos()
actual_end_rot = robot_model.rarm_end_coords.worldrot()
actual_end_pos = robot_model.right_arm_end_coords.worldpos()
actual_end_rot = robot_model.right_arm_end_coords.worldrot()

# Visualize current end-effector position with green coordinate frame
current_ee_axis = skrobot.model.Axis(
Expand Down Expand Up @@ -58,12 +58,12 @@ def demonstrate_revert_if_fail(robot_model, target_coords, link_list, viewer,
result_standard = robot_model.inverse_kinematics(
unreachable_coords,
link_list=link_list,
move_target=robot_model.rarm_end_coords,
move_target=robot_model.right_arm_end_coords,
rotation_axis=True,
revert_if_fail=True # Default behavior
)

standard_end_pos = robot_model.rarm_end_coords.worldpos()
standard_end_pos = robot_model.right_arm_end_coords.worldpos()
success_standard = result_standard is not False and result_standard is not None
print(" Result: {}".format("Success" if success_standard else "Failed"))
print(" End-effector position: {}".format(standard_end_pos))
Expand All @@ -73,7 +73,7 @@ def demonstrate_revert_if_fail(robot_model, target_coords, link_list, viewer,
robot_model.inverse_kinematics(
target_coords, # The original successful target
link_list=link_list,
move_target=robot_model.rarm_end_coords,
move_target=robot_model.right_arm_end_coords,
rotation_axis=True
)

Expand All @@ -86,21 +86,21 @@ def demonstrate_revert_if_fail(robot_model, target_coords, link_list, viewer,
result_progressive = robot_model.inverse_kinematics(
unreachable_coords,
link_list=link_list,
move_target=robot_model.rarm_end_coords,
move_target=robot_model.right_arm_end_coords,
rotation_axis=True,
revert_if_fail=False # Keep partial progress
)
else:
result_progressive = robot_model.inverse_kinematics(
unreachable_coords,
link_list=link_list,
move_target=robot_model.rarm_end_coords,
move_target=robot_model.right_arm_end_coords,
rotation_axis=True,
revert_if_fail=False # Keep partial progress
)

progressive_end_pos = robot_model.rarm_end_coords.worldpos()
progressive_end_rot = robot_model.rarm_end_coords.worldrot()
progressive_end_pos = robot_model.right_arm_end_coords.worldpos()
progressive_end_rot = robot_model.right_arm_end_coords.worldrot()
success_progressive = result_progressive is not False and result_progressive is not None
print(" Result: {}".format("Success" if success_progressive else "Failed (but kept progress)"))
print(" End-effector position: {}".format(progressive_end_pos))
Expand Down Expand Up @@ -234,7 +234,7 @@ def main():
# Build IK kwargs
ik_kwargs = {
'link_list': link_list,
'move_target': robot_model.rarm_end_coords,
'move_target': robot_model.right_arm_end_coords,
'rotation_axis': True,
}
if translation_tolerance is not None:
Expand Down
4 changes: 2 additions & 2 deletions examples/pybullet_robot_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,8 @@ def main():
skrobot.interfaces.pybullet.draw(target_coords)
robot.inverse_kinematics(
target_coords,
link_list=robot.rarm.link_list,
move_target=robot.rarm_end_coords,
link_list=robot.arm.link_list,
move_target=robot.arm_end_coords,
rotation_axis=True,
stop=1000,
)
Expand Down
77 changes: 77 additions & 0 deletions skrobot/model/robot_model.py
Original file line number Diff line number Diff line change
Expand Up @@ -1866,6 +1866,83 @@ def init_pose(self):
self.joint_max_angles)
return self.angle_vector(target_angles)

# New naming convention properties with more intuitive full names.
# These provide access using full names (right_arm, left_arm, etc.)
# while keeping the abbreviated names (rarm, larm, etc.) available for
# backward compatibility.

def _get_limb(self, attr_name):
"""Get limb by attribute name, returning None if not available."""
try:
limb = getattr(self, attr_name, None)
if isinstance(limb, RobotModel):
return limb
except NotImplementedError:
Copy link

Copilot AI Jan 6, 2026

Choose a reason for hiding this comment

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

'except' clause does nothing but pass and there is no explanatory comment.

Copilot uses AI. Check for mistakes.
# Some robot models raise NotImplementedError for unsupported limbs
pass
return None

def _get_end_coords(self, attr_name):
"""Get end coords by attribute name, returning None if not available."""
try:
coords = getattr(self, attr_name, None)
if isinstance(coords, CascadedCoords):
return coords
except NotImplementedError:
Copy link

Copilot AI Jan 6, 2026

Choose a reason for hiding this comment

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

'except' clause does nothing but pass and there is no explanatory comment.

Copilot uses AI. Check for mistakes.
# Some robot models raise NotImplementedError for unsupported coords
pass
return None

@property
def right_arm(self):
"""Right arm kinematic chain (alias for rarm)."""
return self._get_limb('rarm')

@property
def left_arm(self):
"""Left arm kinematic chain (alias for larm)."""
return self._get_limb('larm')

@property
def right_leg(self):
"""Right leg kinematic chain (alias for rleg)."""
return self._get_limb('rleg')

@property
def left_leg(self):
"""Left leg kinematic chain (alias for lleg)."""
return self._get_limb('lleg')

@property
def right_arm_end_coords(self):
"""Right arm end effector coordinates (alias for rarm_end_coords)."""
return self._get_end_coords('rarm_end_coords')

@property
def left_arm_end_coords(self):
"""Left arm end effector coordinates (alias for larm_end_coords)."""
return self._get_end_coords('larm_end_coords')

@property
def right_leg_end_coords(self):
"""Right leg end effector coordinates (alias for rleg_end_coords)."""
return self._get_end_coords('rleg_end_coords')

@property
def left_leg_end_coords(self):
"""Left leg end effector coordinates (alias for lleg_end_coords)."""
return self._get_end_coords('lleg_end_coords')

@property
def arm(self):
"""Arm kinematic chain for single-arm robots (alias for rarm)."""
return self._get_limb('rarm')

@property
def arm_end_coords(self):
"""Arm end effector coordinates for single-arm robots."""
return self._get_end_coords('rarm_end_coords')

def _meshes_from_urdf_visuals(self, visuals):
meshes = []
for visual in visuals:
Expand Down
13 changes: 13 additions & 0 deletions skrobot/models/fetch.py
Original file line number Diff line number Diff line change
Expand Up @@ -85,3 +85,16 @@ def rarm_with_torso(self):
joint_list=rarm_with_torso_joints)
r.end_coords = self.rarm_end_coords
return r

# New naming convention aliases (backward compatible)
@property
def arm(self):
return self.rarm

@property
def arm_with_torso(self):
return self.rarm_with_torso

@property
def arm_end_coords(self):
return self.rarm_end_coords
9 changes: 9 additions & 0 deletions skrobot/models/kuka.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,3 +61,12 @@ def open_hand(self, default_angle=np.deg2rad(10), av=None):
av[-2] = default_angle
av[-4] = -default_angle
return self.angle_vector(av)

# New naming convention aliases (backward compatible)
@property
def arm(self):
return self.rarm

@property
def arm_end_coords(self):
return self.rarm_end_coords
Loading