Skip to content

Commit 2f6d4ba

Browse files
committed
fix qlim
1 parent b08243c commit 2f6d4ba

File tree

1 file changed

+33
-29
lines changed

1 file changed

+33
-29
lines changed

roboticstoolbox/models/DH/AL5D.py

Lines changed: 33 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
from roboticstoolbox import DHRobot, RevoluteMDH
77
from spatialmath import SE3
88

9+
910
class AL5D(DHRobot):
1011
"""
1112
Class that models a Lynxmotion AL5D manipulator
@@ -41,48 +42,50 @@ def __init__(self, symbolic=False):
4142

4243
if symbolic:
4344
import spatialmath.base.symbolic as sym
45+
4446
zero = sym.zero()
4547
pi = sym.pi()
4648
else:
4749
from math import pi
50+
4851
zero = 0.0
4952

5053
# robot length values (metres)
5154
a = [0, 0.002, 0.14679, 0.17751]
5255
d = [-0.06858, 0, 0, 0]
5356

54-
alpha = [pi, pi/2, pi, pi]
55-
offset = [pi/2, pi, -0.0427, -0.0427-pi/2]
57+
alpha = [pi, pi / 2, pi, pi]
58+
offset = [pi / 2, pi, -0.0427, -0.0427 - pi / 2]
5659

5760
# mass data as measured
5861
mass = [0.187, 0.044, 0.207, 0.081]
5962

6063
# center of mass as calculated through CAD model
6164
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-
]
65+
[0.01724, -0.00389, 0.00468],
66+
[0.07084, 0.00000, 0.00190],
67+
[0.05615, -0.00251, -0.00080],
68+
[0.04318, 0.00735, -0.00523],
69+
]
6770

6871
# moments of inertia are practically zero
6972
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-
]
73+
[0, 0, 0, 0, 0, 0],
74+
[0, 0, 0, 0, 0, 0],
75+
[0, 0, 0, 0, 0, 0],
76+
[0, 0, 0, 0, 0, 0],
77+
]
7578

7679
joint_limits = [
77-
[-pi/2, pi/2],
78-
[-pi/2, pi/2],
79-
[-pi,2, pi/2],
80-
[-pi/2, pi/2],
81-
]
80+
[-pi / 2, pi / 2],
81+
[-pi / 2, pi / 2],
82+
[-pi / 2, pi / 2],
83+
[-pi / 2, pi / 2],
84+
]
8285

8386
links = []
8487

85-
for j in range(4):
88+
for j in range(3):
8689
link = RevoluteMDH(
8790
d=d[j],
8891
a=a[j],
@@ -92,27 +95,28 @@ def __init__(self, symbolic=False):
9295
I=moments_of_inertia[j],
9396
G=1,
9497
B=0,
95-
Tc=[0,0],
96-
qlim=joint_limits[j]
98+
Tc=[0, 0],
99+
qlim=joint_limits[j],
97100
)
98101
links.append(link)
99-
100-
tool=SE3(0.07719,0,0)
101-
102+
103+
tool = SE3(0.07719, 0, 0)
104+
102105
super().__init__(
103106
links,
104107
name="AL5D",
105108
manufacturer="Lynxmotion",
106-
keywords=('dynamics', 'symbolic'),
109+
keywords=("dynamics", "symbolic"),
107110
symbolic=symbolic,
108-
tool=tool
111+
tool=tool,
109112
)
110-
113+
111114
# zero angles
112-
self.addconfiguration("home", np.array([pi/2, pi/2, pi/2, pi/2]))
115+
self.addconfiguration("home", np.array([pi / 2, pi / 2, pi / 2, pi / 2]))
116+
113117

114-
if __name__ == '__main__': # pragma nocover
118+
if __name__ == "__main__": # pragma nocover
115119

116120
al5d = AL5D(symbolic=False)
117121
print(al5d)
118-
print(al5d.dyntable())
122+
# print(al5d.dyntable())

0 commit comments

Comments
 (0)