Skip to content

Commit 46d73f9

Browse files
committed
Merge branch 'master' into future
2 parents 24670d9 + 176f21c commit 46d73f9

File tree

15 files changed

+290
-0
lines changed

15 files changed

+290
-0
lines changed

roboticstoolbox/models/DH/AL5D.py

Lines changed: 118 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,118 @@
1+
"""
2+
@author: Tassos Natsakis
3+
"""
4+
5+
import numpy as np
6+
from roboticstoolbox import DHRobot, RevoluteMDH
7+
from spatialmath import SE3
8+
9+
class AL5D(DHRobot):
10+
"""
11+
Class that models a Lynxmotion AL5D manipulator
12+
13+
:param symbolic: use symbolic constants
14+
:type symbolic: bool
15+
16+
``AL5D()`` is an object which models a Lynxmotion AL5D robot and
17+
describes its kinematic and dynamic characteristics using modified DH
18+
conventions.
19+
20+
.. runblock:: pycon
21+
22+
>>> import roboticstoolbox as rtb
23+
>>> robot = rtb.models.DH.AL5D()
24+
>>> print(robot)
25+
26+
Defined joint configurations are:
27+
28+
- qz, zero joint angle configuration
29+
30+
.. note::
31+
- SI units are used.
32+
33+
:References:
34+
35+
- 'Reference of the robot <http://www.lynxmotion.com/c-130-al5d.aspx>'_
36+
37+
.. codeauthor:: Tassos Natsakis
38+
""" # noqa
39+
40+
def __init__(self, symbolic=False):
41+
42+
if symbolic:
43+
import spatialmath.base.symbolic as sym
44+
zero = sym.zero()
45+
pi = sym.pi()
46+
else:
47+
from math import pi
48+
zero = 0.0
49+
50+
# robot length values (metres)
51+
a = [0, 0.002, 0.14679, 0.17751]
52+
d = [-0.06858, 0, 0, 0]
53+
54+
alpha = [pi, pi/2, pi, pi]
55+
offset = [pi/2, pi, -0.0427, -0.0427-pi/2]
56+
57+
# mass data as measured
58+
mass = [0.187, 0.044, 0.207, 0.081]
59+
60+
# center of mass as calculated through CAD model
61+
center_of_mass = [
62+
[0.01724, -0.00389, 0.00468],
63+
[0.07084, 0.00000, 0.00190],
64+
[0.05615, -0.00251, -0.00080],
65+
[0.04318, 0.00735, -0.00523],
66+
]
67+
68+
# moments of inertia are practically zero
69+
moments_of_inertia = [
70+
[0, 0, 0, 0, 0, 0],
71+
[0, 0, 0, 0, 0, 0],
72+
[0, 0, 0, 0, 0, 0],
73+
[0, 0, 0, 0, 0, 0]
74+
]
75+
76+
joint_limits = [
77+
[-pi/2, pi/2],
78+
[-pi/2, pi/2],
79+
[-pi,2, pi/2],
80+
[-pi/2, pi/2],
81+
]
82+
83+
links = []
84+
85+
for j in range(4):
86+
link = RevoluteMDH(
87+
d=d[j],
88+
a=a[j],
89+
alpha=alpha[j],
90+
offset=offset[j],
91+
r=center_of_mass[j],
92+
I=moments_of_inertia[j],
93+
G=1,
94+
B=0,
95+
Tc=[0,0],
96+
qlim=joint_limits[j]
97+
)
98+
links.append(link)
99+
100+
tool=SE3(0.07719,0,0)
101+
102+
super().__init__(
103+
links,
104+
name="AL5D",
105+
manufacturer="Lynxmotion",
106+
keywords=('dynamics', 'symbolic'),
107+
symbolic=symbolic,
108+
tool=tool
109+
)
110+
111+
# zero angles
112+
self.addconfiguration("home", np.array([pi/2, pi/2, pi/2, pi/2]))
113+
114+
if __name__ == '__main__': # pragma nocover
115+
116+
al5d = AL5D(symbolic=False)
117+
print(al5d)
118+
print(al5d.dyntable())

roboticstoolbox/models/DH/__init__.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
from roboticstoolbox.models.DH.TwoLink import TwoLink
2222
from roboticstoolbox.models.DH.Hyper3d import Hyper3d
2323
from roboticstoolbox.models.DH.P8 import P8
24+
from roboticstoolbox.models.DH.AL5D import AL5D
2425

2526

2627
__all__ = [
@@ -47,4 +48,5 @@
4748
'Baxter',
4849
'TwoLink',
4950
'P8',
51+
'AL5D',
5052
]

roboticstoolbox/models/URDF/AL5D.py

Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,53 @@
1+
#!/usr/bin/env python
2+
3+
import numpy as np
4+
from roboticstoolbox.robot.ERobot import ERobot
5+
from math import pi
6+
7+
class AL5D(ERobot):
8+
"""
9+
Class that imports a AL5D URDF model
10+
11+
``AL5D()`` is a class which imports a Lynxmotion AL5D robot definition
12+
from a URDF file. The model describes its kinematic and graphical
13+
characteristics.
14+
15+
.. runblock:: pycon
16+
17+
>>> import roboticstoolbox as rtb
18+
>>> robot = rtb.models.URDF.AL5D()
19+
>>> print(robot)
20+
21+
Defined joint configurations are:
22+
23+
- qz, zero joint angle configuration, 'L' shaped configuration
24+
- up, robot poiting upwards
25+
26+
.. codeauthor:: Tassos Natsakis
27+
"""
28+
29+
def __init__(self):
30+
31+
links, name, urdf_string, urdf_filepath = self.URDF_read(
32+
"al5d_description/urdf/al5d_robot.urdf"
33+
)
34+
35+
super().__init__(
36+
links,
37+
name=name,
38+
urdf_string=urdf_string,
39+
urdf_filepath=urdf_filepath,
40+
)
41+
42+
self.manufacturer = "Lynxmotion"
43+
44+
# zero angles, upper arm pointing up, lower arm straight ahead
45+
self.addconfiguration("qz", np.array([0, 0, 0, 0]))
46+
47+
# reference pose robot pointing upwards
48+
self.addconfiguration("up", np.array([0.0000, 0.0000, 1.5707, 0.0000]))
49+
50+
if __name__ == "__main__": # pragma nocover
51+
52+
robot = AL5D()
53+
print(robot)

roboticstoolbox/models/URDF/__init__.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
from roboticstoolbox.models.URDF.KinovaGen3 import KinovaGen3
2121
from roboticstoolbox.models.URDF.YuMi import YuMi
2222
from roboticstoolbox.models.URDF.Valkyrie import Valkyrie
23+
from roboticstoolbox.models.URDF.AL5D import AL5D
2324

2425
__all__ = [
2526
"Panda",
@@ -44,4 +45,5 @@
4445
"KinovaGen3",
4546
"YuMi",
4647
"Valkyrie",
48+
"AL5D",
4749
]
611 KB
Binary file not shown.
343 KB
Binary file not shown.
111 KB
Binary file not shown.
681 KB
Binary file not shown.
1.11 MB
Binary file not shown.
611 KB
Binary file not shown.

0 commit comments

Comments
 (0)