Skip to content
Merged
Show file tree
Hide file tree
Changes from 3 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
15 changes: 14 additions & 1 deletion examples/batch_ik_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
from skrobot.coordinates import Coordinates
from skrobot.model.primitives import Axis
from skrobot.models import Fetch
from skrobot.models import Nextage
from skrobot.models import Panda
from skrobot.models import PR2
from skrobot.models import R8_6
Expand All @@ -27,7 +28,7 @@ def parse_axis_constraint(axis_str):
def main():
parser = argparse.ArgumentParser(description='Advanced Batch IK Demo with axis constraints')
parser.add_argument('--robot', type=str, default='pr2',
choices=['fetch', 'pr2', 'panda', 'r8_6'],
choices=['fetch', 'pr2', 'panda', 'r8_6', 'nextage'],
help='Robot model to use. Default: fetch')
parser.add_argument('--rotation-axis', '--rotation_axis', '-r',
default='True',
Expand Down Expand Up @@ -80,6 +81,9 @@ def main():
elif args.robot == 'r8_6':
robot = R8_6()
arm = robot.rarm
elif args.robot == 'nextage':
robot = Nextage()
arm = robot.rarm

robot.reset_pose()

Expand All @@ -98,6 +102,15 @@ def main():
Coordinates(pos=(0.46, -0.24, 0.89)).rotate(np.deg2rad(8), 'z').rotate(np.deg2rad(3), 'x'),
Coordinates(pos=(0.56, -0.24, 0.89)),
]
elif args.robot == 'nextage':
target_poses = [
Coordinates(pos=(0.2, -0.3, 0.0)).rotate(np.deg2rad(-25), 'z'),
Coordinates(pos=(0.2, -0.3, -0.05)).rotate(np.deg2rad(-30), 'z'),
Coordinates(pos=(0.35, -0.25, 0.05)).rotate(np.deg2rad(35), 'y').rotate(np.deg2rad(-20), 'z'),
Coordinates(pos=(0.1, -0.1, 0.1)).rotate(np.deg2rad(90), 'x'),
Coordinates(pos=(0.2, -0.1, 0.03)).rotate(np.deg2rad(45), 'x'),
Coordinates(pos=(0.35, -0.15, 0.1)).rotate(np.deg2rad(-80), 'y').rotate(np.deg2rad(15), 'z'),
]
else:
# Default target poses for Fetch/PR2/Panda
target_poses = [
Expand Down
3 changes: 2 additions & 1 deletion examples/robot_models.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ def main():
robots = [
skrobot.models.Kuka(),
skrobot.models.Fetch(),
skrobot.models.Nextage(),
skrobot.models.PR2(),
skrobot.models.Panda(),
]
Expand All @@ -49,7 +50,7 @@ def main():
for i in range(nrow):
for j in range(ncol):
try:
robot = robots[i * nrow + j]
robot = robots[i * ncol + j]
except IndexError:
break
plane = skrobot.model.Box(extents=(row - 0.01, col - 0.01, 0.01))
Expand Down
14 changes: 14 additions & 0 deletions skrobot/data/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,20 @@ def kuka_urdfpath():
return osp.join(data_dir, 'kuka_description', 'kuka.urdf')


def nextage_urdfpath():
path = osp.join(get_cache_dir(), 'nextage_description', 'urdf', 'NextageOpen.urdf')
if osp.exists(path):
return path
_download(
url='https://github.com/Michi-Tsubaki/scikit-robot-models/raw/refs/heads/add-nextage/nextage_description.tar.gz', # NOQA
Copy link
Owner

Choose a reason for hiding this comment

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

iory/scikit-robot-models#1
This PR is merged. Please fix the url.

path=osp.join(get_cache_dir(), 'nextage_description.tar.gz'),
md5='9805ac9cd97b67056dde31aa88762ec7',
postprocess='extractall',
quiet=True,
)
return path


def panda_urdfpath():
path = osp.join(get_cache_dir(),
'franka_description', 'panda.urdf')
Expand Down
5 changes: 3 additions & 2 deletions skrobot/interfaces/ros/__init__.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
from skrobot._lazy_imports import LazyImportClass


NextageROSRobotInterface = LazyImportClass(
".nextage", "NextageROSRobotInterface", "skrobot.interfaces.ros")
PandaROSRobotInterface = LazyImportClass(
".panda", "PandaROSRobotInterface", "skrobot.interfaces.ros")
PR2ROSRobotInterface = LazyImportClass(
".pr2", "PR2ROSRobotInterface", "skrobot.interfaces.ros")

__all__ = ["PandaROSRobotInterface", "PR2ROSRobotInterface"]
__all__ = ["NextageROSRobotInterface", "PandaROSRobotInterface", "PR2ROSRobotInterface"]
59 changes: 59 additions & 0 deletions skrobot/interfaces/ros/nextage.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
import actionlib
import control_msgs.msg

from .base import ROSRobotInterfaceBase


class NextageROSRobotInterface(ROSRobotInterfaceBase):

def __init__(self, *args, **kwargs):
super(NextageROSRobotInterface, self).__init__(*args, **kwargs)

self.rarm_move = actionlib.SimpleActionClient(
'/rarm_controller/follow_joint_trajectory_action',
control_msgs.msg.FollowJointTrajectoryAction
)
self.rarm_move.wait_for_server()

self.larm_move = actionlib.SimpleActionClient(
'/larm_controller/follow_joint_trajectory_action',
control_msgs.msg.FollowJointTrajectoryAction
)
self.larm_move.wait_for_server()

@property
def rarm_controller(self):
return dict(
controller_type='rarm_controller',
controller_action='/rarm_controller/follow_joint_trajectory_action',
controller_state='/rarm_controller/state',
action_type=control_msgs.msg.FollowJointTrajectoryAction,
joint_names=[j.name for j in self.robot.rarm.joint_list],
)

@property
def larm_controller(self):
return dict(
controller_type='larm_controller',
controller_action='/larm_controller/follow_joint_trajectory_action',
controller_state='/larm_controller/state',
action_type=control_msgs.msg.FollowJointTrajectoryAction,
joint_names=[j.name for j in self.robot.larm.joint_list],
)

def default_controller(self):
return [self.rarm_controller, self.larm_controller]

def move_arm(self, trajectory, arm='rarm', wait=True):
if arm == 'rarm':
self.send_trajectory(self.rarm_move, trajectory, wait)
elif arm == 'larm':
self.send_trajectory(self.larm_move, trajectory, wait)

def send_trajectory(self, client, trajectory, wait=True):
goal = control_msgs.msg.FollowJointTrajectoryGoal()
goal.trajectory = trajectory
if wait:
client.send_goal_and_wait(goal)
else:
client.send_goal(goal)
1 change: 1 addition & 0 deletions skrobot/models/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

from skrobot.models.fetch import Fetch
from skrobot.models.kuka import Kuka
from skrobot.models.nextage import Nextage
from skrobot.models.panda import Panda
from skrobot.models.pr2 import PR2
from skrobot.models.r8_6 import R8_6
80 changes: 80 additions & 0 deletions skrobot/models/nextage.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
from cached_property import cached_property

from ..data import nextage_urdfpath
from ..model import RobotModel
from .urdf import RobotModelFromURDF


class Nextage(RobotModelFromURDF):

"""
- Nextage Open Official Information.

https://nextage.kawadarobot.co.jp/open

- Nextage Open Robot Description

https://github.com/tork-a/rtmros_nextage/tree/indigo-devel/nextage_description/urdf
"""

def __init__(self, *args, **kwargs):
super(Nextage, self).__init__(*args, **kwargs)
self.reset_pose()

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

def reset_pose(self):
import numpy as np
angle_vector = [
0.0,
-0.5, 0.0, np.deg2rad(-100), np.deg2rad(15.2), np.deg2rad(9.4), np.deg2rad(3.2),
0.5, 0.0, np.deg2rad(-100), np.deg2rad(-15.2), np.deg2rad(9.4), np.deg2rad(-3.2),
0.0, 0.0
]
self.angle_vector(angle_vector)
return self.angle_vector()

def reset_manip_pose(self):
"""Reset robot to manipulation pose (same as reset_pose for Nextage)"""
return self.reset_pose()

@cached_property
def rarm(self):
link_names = ['RARM_JOINT{}_Link'.format(i) for i in range(6)]
links = [getattr(self, n) for n in link_names]
joints = [l.joint for l in links]
model = RobotModel(link_list=links, joint_list=joints)
model.end_coords = self.rarm_end_coords
return model

@cached_property
def larm(self):
link_names = ['LARM_JOINT{}_Link'.format(i) for i in range(6)]
links = [getattr(self, n) for n in link_names]
joints = [l.joint for l in links]
model = RobotModel(link_list=links, joint_list=joints)
model.end_coords = self.larm_end_coords
return model

@cached_property
def head(self):
link_names = ['HEAD_JOINT{}_Link'.format(i) for i in range(2)]
links = [getattr(self, n) for n in link_names]
joints = [l.joint for l in links]
model = RobotModel(link_list=links, joint_list=joints)
model.end_coords = self.head_end_coords
return model

@cached_property
def rarm_end_coords(self):
return self.RARM_JOINT5_Link

@cached_property
def larm_end_coords(self):
return self.LARM_JOINT5_Link

@cached_property
def head_end_coords(self):
return self.HEAD_JOINT1_Link
Loading