Skip to content

Commit 1aa845e

Browse files
author
Rhys
committed
merge with updates
2 parents f144168 + 176f21c commit 1aa845e

File tree

18 files changed

+320
-9
lines changed

18 files changed

+320
-9
lines changed

.github/workflows/future_testing.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ jobs:
1111
strategy:
1212
matrix:
1313
os: [windows-latest, ubuntu-latest, macos-latest]
14-
python-version: [3.6, 3.7, 3.8, 3.9]
14+
python-version: [3.7, 3.8, 3.9]
1515

1616
steps:
1717
- name: Set up Python ${{ matrix.python-version }}

.github/workflows/pythonpackage.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ jobs:
1414
strategy:
1515
matrix:
1616
os: [windows-latest, ubuntu-latest, macos-latest]
17-
python-version: [3.6, 3.7, 3.8, 3.9]
17+
python-version: [3.7, 3.8, 3.9]
1818
steps:
1919
- uses: actions/checkout@v2
2020
- name: Set up Python ${{ matrix.python-version }}

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/Panda.py

Lines changed: 28 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -46,49 +46,70 @@ def __init__(self):
4646
a=0.0,
4747
d=0.333,
4848
alpha=0.0,
49-
qlim=np.array([-2.8973, 2.8973])
49+
qlim=np.array([-2.8973, 2.8973]),
50+
m=4.970684,
51+
I = [7.03370e-01, 7.06610e-01, 9.11700e-03,-1.39000e-04, 1.91690e-02, 6.77200e-03],
52+
G= 1
5053
),
5154

5255
RevoluteMDH(
5356
a=0.0,
5457
d=0.0,
5558
alpha=-np.pi/2,
56-
qlim=np.array([-1.7628, 1.7628])
59+
qlim=np.array([-1.7628, 1.7628]),
60+
m= 0.646926,
61+
I = [7.96200e-03, 2.81100e-02, 2.59950e-02, -3.92500e-03, 7.04000e-04, 1.02540e-02],
62+
G= 1
5763
),
5864

5965
RevoluteMDH(
6066
a=0.0,
6167
d=0.316,
6268
alpha=np.pi/2,
63-
qlim=np.array([-2.8973, 2.8973])
69+
qlim=np.array([-2.8973, 2.8973]),
70+
m= 3.228604,
71+
I = [3.72420e-02, 3.61550e-02, 1.08300e-02, -4.76100e-03, -1.28050e-02, -1.13960e-02],
72+
G= 1
6473
),
6574

6675
RevoluteMDH(
6776
a=0.0825,
6877
d=0.0,
6978
alpha=np.pi/2,
70-
qlim=np.array([-3.0718, -0.0698])
79+
qlim=np.array([-3.0718, -0.0698]),
80+
m= 3.587895,
81+
I =[2.58530e-02, 1.95520e-02, 2.83230e-02, 7.79600e-03, 8.64100e-03, -1.33200e-03],
82+
G= 1
7183
),
7284

7385
RevoluteMDH(
7486
a=-0.0825,
7587
d=0.384,
7688
alpha=-np.pi/2,
77-
qlim=np.array([-2.8973, 2.8973])
89+
qlim=np.array([-2.8973, 2.8973]),
90+
m= 1.225946,
91+
I = [3.55490e-02, 2.94740e-02, 8.62700e-03, -2.11700e-03, 2.29000e-04, -4.03700e-03],
92+
G= 1
7893
),
7994

8095
RevoluteMDH(
8196
a=0.0,
8297
d=0.0,
8398
alpha=np.pi/2,
84-
qlim=np.array([-0.0175, 3.7525])
99+
qlim=np.array([-0.0175, 3.7525]),
100+
m= 1.666555,
101+
I = [1.96400e-03, 4.35400e-03, 5.43300e-03, 1.09000e-04, 3.41000e-04, -1.15800e-03],
102+
G= 1
85103
),
86104

87105
RevoluteMDH(
88106
a=0.088,
89107
d=flange,
90108
alpha=np.pi/2,
91-
qlim=np.array([-2.8973, 2.8973])
109+
qlim=np.array([-2.8973, 2.8973]),
110+
m=7.35522e-01,
111+
I = [1.25160e-02, 1.00270e-02, 4.81500e-03, -4.28000e-04, -7.41000e-04, -1.19600e-03],
112+
G= 1
92113
)
93114
]
94115

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
]
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
@@ -21,6 +21,7 @@
2121
from roboticstoolbox.models.URDF.YuMi import YuMi
2222
from roboticstoolbox.models.URDF.Fetch import Fetch
2323
from roboticstoolbox.models.URDF.FetchCamera import FetchCamera
24+
from roboticstoolbox.models.URDF.AL5D import AL5D
2425

2526
__all__ = [
2627
"Panda",
@@ -46,4 +47,5 @@
4647
"YuMi",
4748
"Fetch",
4849
"FetchCamera",
50+
"AL5D",
4951
]
611 KB
Binary file not shown.
343 KB
Binary file not shown.
111 KB
Binary file not shown.

0 commit comments

Comments
 (0)