-
Notifications
You must be signed in to change notification settings - Fork 561
Expand file tree
/
Copy pathWAM.py
More file actions
68 lines (47 loc) · 1.65 KB
/
WAM.py
File metadata and controls
68 lines (47 loc) · 1.65 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
#!/usr/bin/env python
import numpy as np
from roboticstoolbox.robot.ERobot import ERobot, ERobot2
from spatialmath import SE3
class WAM(ERobot):
"""
Class that imports a WAM URDF model
``WAM()`` is a class which imports a Barrett WAM robot definition
from a URDF file. The model describes its kinematic and graphical
characteristics.
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.URDF.WAM()
>>> print(robot)
Defined joint configurations are:
- qz, zero joint angle configuration, 'L' shaped configuration
- qr, vertical 'READY' configuration
- qs, arm is stretched out in the x-direction
- qn, arm is at a nominal non-singular configuration
.. codeauthor:: Longsen Gao
.. sectionauthor:: Peter Corke
"""
def __init__(self):
links, name, urdf_string, urdf_filepath = self.URDF_read(
"wam_description/urdf/wam7.urdf.xacro"
)
super().__init__(
links,
name=name,
manufacturer="Barrett Robtoics",
gripper_links=links[8],
urdf_string=urdf_string,
urdf_filepath=urdf_filepath,
)
self.grippers[0].tool = SE3(0, 0, 0)
self.qdlim = np.array(
[2.1750, 2.1750, 2.1750, 2.1750, 2.6100, 2.6100, 2.6100, 3.0, 3.0]
)
self.qr = np.array([0, 0, 0, 0, 0, 0, 0])
self.qz = np.zeros(7)
self.addconfiguration("qr", self.qr)
self.addconfiguration("qz", self.qz)
if __name__ == "__main__": # pragma nocover
r = WAM()
r.qz
for link in r.grippers[0].links:
print(link)