Skip to content

Commit 927b1e1

Browse files
KenMat765iory
authored andcommitted
Add RoverArmedTycoon RobotModel
1 parent 76c2168 commit 927b1e1

File tree

4 files changed

+107
-0
lines changed

4 files changed

+107
-0
lines changed

skrobot/data/__init__.py

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -126,3 +126,18 @@ def pr2_urdfpath():
126126

127127
def r8_6_urdfpath():
128128
return osp.join(data_dir, 'robot_descriptions', 'urdf', 'r8_6.urdf')
129+
130+
131+
def rover_armed_tycoon_urdfpath():
132+
path = osp.join(get_cache_dir(),
133+
'tycoon_description', 'urdf', 'tycoon_arm_assem.urdf')
134+
if osp.exists(path):
135+
return path
136+
_download(
137+
url='https://github.com/iory/scikit-robot-models/raw/main/tycoon_description.tar.gz',
138+
path=osp.join(get_cache_dir(), 'tycoon_description.tar.gz'),
139+
md5='166ab45ed6e9b24bfb8d0f7a7eb19186',
140+
postprocess='extractall',
141+
quiet=True,
142+
)
143+
return path

skrobot/models/__init__.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,3 +6,4 @@
66
from skrobot.models.panda import Panda
77
from skrobot.models.pr2 import PR2
88
from skrobot.models.r8_6 import R8_6
9+
from skrobot.models.tycoon import RoverArmedTycoon

skrobot/models/tycoon.py

Lines changed: 82 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
1+
from cached_property import cached_property
2+
import numpy as np
3+
4+
from skrobot.coordinates import CascadedCoords
5+
from skrobot.data import rover_armed_tycoon_urdfpath
6+
from skrobot.model import RobotModel
7+
from skrobot.models.urdf import RobotModelFromURDF
8+
9+
10+
class RoverArmedTycoon(RobotModelFromURDF):
11+
"""Rover Armed Tycoon Robot Model."""
12+
13+
def __init__(self, *args, **kwargs):
14+
super(RoverArmedTycoon, self).__init__(*args, **kwargs)
15+
16+
self._arm_end_coords = CascadedCoords(
17+
parent=self.tycoon_7_roll_link,
18+
pos=[-0.05, 0, 0],
19+
name='arm_end_coords')
20+
self._arm_end_coords.rotate(np.pi, 'z')
21+
22+
@cached_property
23+
def default_urdf_path(self):
24+
return rover_armed_tycoon_urdfpath()
25+
26+
@cached_property
27+
def arm(self):
28+
"""Arm kinematic chain."""
29+
links = [
30+
self.tycoon_0_pitch_link,
31+
self.tycoon_0_roll_link,
32+
self.tycoon_1_pitch_link,
33+
self.tycoon_1_roll_link,
34+
self.tycoon_2_pitch_link,
35+
self.tycoon_2_roll_link,
36+
self.tycoon_3_pitch_link,
37+
self.tycoon_3_roll_link,
38+
self.tycoon_4_pitch_link,
39+
self.tycoon_4_roll_link,
40+
self.tycoon_5_pitch_link,
41+
self.tycoon_5_roll_link,
42+
self.tycoon_6_pitch_link,
43+
self.tycoon_6_roll_link,
44+
self.tycoon_7_pitch_link,
45+
self.tycoon_7_roll_link,
46+
]
47+
joints = [link.joint for link in links]
48+
model = RobotModel(link_list=links, joint_list=joints)
49+
model.end_coords = self._arm_end_coords
50+
return model
51+
52+
@property
53+
def arm_end_coords(self):
54+
"""End coordinates for arm."""
55+
return self._arm_end_coords
56+
57+
def reset_pose(self):
58+
self.init_pose()
59+
self.tycoon_3_pitch_joint.joint_angle(0.5)
60+
self.tycoon_4_pitch_joint.joint_angle(0.5)
61+
self.tycoon_5_pitch_joint.joint_angle(-0.5)
62+
self.tycoon_6_pitch_joint.joint_angle(-0.5)
63+
64+
65+
if __name__ == '__main__':
66+
from skrobot.models import Axis
67+
from skrobot.models import RoverArmedTycoon
68+
from skrobot.viewers import PyrenderViewer
69+
70+
robot = RoverArmedTycoon()
71+
robot.reset_pose()
72+
73+
viewer = PyrenderViewer()
74+
viewer.add(robot)
75+
76+
axis_arm = Axis.from_coords(robot.arm_end_coords, axis_radius=0.01, axis_length=0.1)
77+
viewer.add(axis_arm)
78+
79+
viewer.show()
80+
81+
while viewer.is_active:
82+
viewer.redraw()
Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
import unittest
2+
3+
import skrobot
4+
5+
6+
class TestTycoon(unittest.TestCase):
7+
8+
def test_init(self):
9+
skrobot.models.RoverArmedTycoon()

0 commit comments

Comments
 (0)