Skip to content

Commit 66bcd03

Browse files
author
Rhys
committed
added fetchcamera
1 parent a0e5002 commit 66bcd03

File tree

1 file changed

+75
-0
lines changed

1 file changed

+75
-0
lines changed
Lines changed: 75 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,75 @@
1+
#!/usr/bin/env python
2+
3+
import numpy as np
4+
from roboticstoolbox.robot.ERobot import ERobot
5+
from spatialmath import SE3
6+
7+
8+
class FetchCamera(ERobot):
9+
"""
10+
Class that imports a Fetch URDF model
11+
12+
``Fetch()`` is a class which imports a Fetch robot definition
13+
from a URDF file. The model describes its kinematic and graphical
14+
characteristics.
15+
16+
.. runblock:: pycon
17+
18+
>>> import roboticstoolbox as rtb
19+
>>> robot = rtb.models.URDF.Fetch()
20+
>>> print(robot)
21+
22+
Defined joint configurations are:
23+
24+
- qz, zero joint angle configuration, 'L' shaped configuration
25+
- qr, vertical 'READY' configuration
26+
- qs, arm is stretched out in the x-direction
27+
- qn, arm is at a nominal non-singular configuration
28+
29+
.. codeauthor:: Jesse Haviland
30+
.. sectionauthor:: Peter Corke
31+
"""
32+
33+
def __init__(self):
34+
35+
links, name, urdf_string, urdf_filepath = self.URDF_read(
36+
"fetch_description/robots/fetch_camera.urdf"
37+
)
38+
39+
super().__init__(
40+
links,
41+
name=name,
42+
manufacturer="Fetch",
43+
gripper_links=links[6],
44+
urdf_string=urdf_string,
45+
urdf_filepath=urdf_filepath,
46+
)
47+
48+
# self.grippers[0].tool = SE3(0, 0, 0.1034)
49+
self.qdlim = np.array(
50+
[4.0, 4.0, 0.1, 1.57, 1.57]
51+
)
52+
53+
self.addconfiguration("qz", np.array([0, 0, 0, 0, 0]))
54+
55+
self.addconfiguration(
56+
"qr", np.array([0, 0, 0, 0, 0])
57+
)
58+
59+
60+
if __name__ == "__main__": # pragma nocover
61+
62+
robot = FetchCamera()
63+
print(robot)
64+
65+
for link in robot.links:
66+
print(link.name)
67+
print(link.isjoint)
68+
print(len(link.collision))
69+
70+
print()
71+
72+
for link in robot.grippers[0].links:
73+
print(link.name)
74+
print(link.isjoint)
75+
print(len(link.collision))

0 commit comments

Comments
 (0)