Skip to content

Commit 01ef378

Browse files
committed
Restructured project. Created setup.py for pip install
1 parent 6740dc4 commit 01ef378

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

60 files changed

+362
-6803
lines changed

I pushed this.txt

Whitespace-only changes.

README.md

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,4 @@
11
# robotics-toolbox-python
22
Robotics Toolbox for Python
33

4-
This is an old first attempt at creating an open Python version of the venerable Robotics Toolbox for MATLAB.
5-
6-
A more active Python port is [robopy](https://github.com/adityadua24/robopy).
4+
This is an attempt at creating an open Python version of the venerable Robotics Toolbox for MATLAB.

roboticstoolbox/__init__.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
from roboticstoolbox.robot import *
2+
from roboticstoolbox.models import *

rtb/models/Panda.py renamed to roboticstoolbox/models/Panda.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
#!/usr/bin/env python
22

33
import numpy as np
4-
from rtb.robot.ets import ets, et
4+
from roboticstoolbox.robot.ets import ets, et
55
# from rtb.tools.transform import transl, xyzrpy_to_trans
66

77

File renamed without changes.

roboticstoolbox/models/__init__.py

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
# Robot Models
2+
from roboticstoolbox.models.Panda import Panda
3+
# from roboticstoolbox.models.PandaMDH import PandaMDH
4+
5+
__all__ = [
6+
'Panda'
7+
# 'PandaMDH'
8+
]

roboticstoolbox/robot/Link.py

Lines changed: 345 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,345 @@
1+
"""
2+
Link object.
3+
Python implementation by: Luis Fernando Lara Tobar and Peter Corke.
4+
Based on original Robotics Toolbox for Matlab code by Peter Corke.
5+
Permission to use and copy is granted provided that acknowledgement of
6+
the authors is made.
7+
@author: Luis Fernando Lara Tobar and Peter Corke
8+
"""
9+
10+
from numpy import *
11+
from utility import *
12+
from transform import *
13+
import copy
14+
15+
16+
class Link:
17+
"""
18+
LINK create a new LINK object
19+
A LINK object holds all information related to a robot link such as
20+
kinematics of the joint
21+
- alpha; the link twist angle
22+
- an; the link length
23+
- theta; the link rotation angle
24+
- dn; the link offset
25+
- sigma; 0 for a revolute joint, non-zero for prismatic
26+
27+
rigid-body inertial parameters
28+
- I; 3x3 inertia matrix about link COG
29+
- m; link mass
30+
- r; link COG wrt link coordinate frame 3x1
31+
motor and transmission parameters
32+
- B; link viscous friction (motor referred)
33+
- Tc; link Coulomb friction 1 element if symmetric, else 2
34+
- G; gear ratio
35+
- Jm; inertia (motor referred)
36+
and miscellaneous
37+
- qlim; joint limit matrix [lower upper] 2 x 1
38+
- offset; joint coordinate offset
39+
Handling the different kinematic conventions is now hidden within the LINK
40+
object.
41+
Conceivably all sorts of stuff could live in the LINK object such as
42+
graphical models of links and so on.
43+
@see: L{Robot}
44+
"""
45+
46+
LINK_DH = 1
47+
LINK_MDH = 2
48+
49+
def __init__(self, alpha=0, A=0, theta=0, D=0, sigma=0, convention=LINK_DH):
50+
"""
51+
L = LINK([alpha A theta D])
52+
L =LINK([alpha A theta D sigma])
53+
L =LINK([alpha A theta D sigma offset])
54+
L =LINK([alpha A theta D], CONVENTION)
55+
L =LINK([alpha A theta D sigma], CONVENTION)
56+
L =LINK([alpha A theta D sigma offset], CONVENTION)
57+
If sigma or offset are not provided they default to zero. Offset is a
58+
constant amount added to the joint angle variable before forward kinematics
59+
and is useful if you want the robot to adopt a 'sensible' pose for zero
60+
joint angle configuration.
61+
The optional CONVENTION argument is 'standard' for standard D&H parameters
62+
or 'modified' for modified D&H parameters. If not specified the default
63+
'standard'.
64+
"""
65+
self.alpha = alpha
66+
self.A = A
67+
self.theta = theta
68+
self.D = D
69+
self.sigma = sigma
70+
self.convention = convention
71+
72+
# we know nothing about the dynamics
73+
self.m = None
74+
self.r = None
75+
self.v = None
76+
self.I = None
77+
self.Jm = None
78+
self.G = None
79+
self.B = None
80+
self.Tc = None
81+
self.qlim = None
82+
83+
return None
84+
85+
def __repr__(self):
86+
87+
if self.convention == Link.LINK_DH:
88+
conv = 'std'
89+
else:
90+
conv = 'mod'
91+
92+
if self.sigma == 0:
93+
jtype = 'R'
94+
else:
95+
jtype = 'P'
96+
97+
if self.D == None:
98+
return "alpha=%f, A=%f, theta=%f jtype: (%c) conv: (%s)" % (self.alpha,
99+
self.A, self.theta, jtype, conv)
100+
elif self.theta == None:
101+
return "alpha=%f, A=%f, D=%f jtype: (%c) conv: (%s)" % (self.alpha,
102+
self.A, self.D, jtype, conv)
103+
else:
104+
return "alpha=%f, A=%f, theta=%f, D=%f jtype: (%c) conv: (%s)" % (self.alpha,
105+
self.A, self.theta, self.D, jtype, conv)
106+
107+
# invoked at print
108+
def __str__(self):
109+
if self.convention == Link.LINK_DH:
110+
conv = 'std'
111+
else:
112+
conv = 'mod'
113+
114+
if self.sigma == 0:
115+
jtype = 'R'
116+
else:
117+
jtype = 'P'
118+
119+
if self.D == None:
120+
return "alpha = %f\tA = %f\ttheta = %f\t--\tjtype: %c\tconv: (%s)" % (
121+
self.alpha, self.A, self.theta, jtype, conv)
122+
elif self.theta == None:
123+
return "alpha = %f\tA = %f\t--\tD = %f\tjtype: %c\tconv: (%s)" % (
124+
self.alpha, self.A, self.D, jtype, conv)
125+
else:
126+
return "alpha = %f\tA = %f\ttheta = %f\tD=%f\tjtype: %c\tconv: (%s)" % (
127+
self.alpha, self.A, self.theta, self.D, jtype, conv)
128+
129+
130+
def display(self):
131+
132+
print self;
133+
print
134+
135+
if self.m != None:
136+
print "m:", self.m
137+
if self.r != None:
138+
print "r:", self.r
139+
if self.I != None:
140+
print "I:\n", self.I
141+
if self.Jm != None:
142+
print "Jm:", self.Jm
143+
if self.B != None:
144+
print "B:", self.B
145+
if self.Tc != None:
146+
print "Tc:", self.Tc
147+
if self.G != None:
148+
print "G:", self.G
149+
if self.qlim != None:
150+
print "qlim:\n", self.qlim
151+
152+
def copy(self):
153+
"""
154+
Return copy of this Link
155+
"""
156+
return copy.copy(self);
157+
158+
def friction(self, qd):
159+
"""
160+
Compute friction torque for joint rate C{qd}.
161+
Depending on fields in the Link object viscous and/or Coulomb friction
162+
are computed.
163+
164+
@type qd: number
165+
@param qd: joint rate
166+
@rtype: number
167+
@return: joint friction torque
168+
"""
169+
tau = 0.0
170+
if isinstance(qd, (ndarray, matrix)):
171+
qd = qd.flatten().T
172+
if self.B == None:
173+
self.B = 0
174+
tau = self.B * qd
175+
if self.Tc == None:
176+
self.Tc = mat([0,0])
177+
tau = tau + (qd > 0) * self.Tc[0,0] + (qd < 0) * self.Tc[0,1]
178+
return tau
179+
180+
def nofriction(self, all=False):
181+
"""
182+
Return a copy of the Link object with friction parameters set to zero.
183+
184+
@type all: boolean
185+
@param all: if True then also zero viscous friction
186+
@rtype: Link
187+
@return: Copy of original Link object with zero friction
188+
@see: L{robot.nofriction}
189+
"""
190+
191+
l2 = self.copy()
192+
193+
l2.Tc = array([0, 0])
194+
if all:
195+
l2.B = 0
196+
return l2;
197+
198+
199+
# methods to set kinematic or dynamic parameters
200+
201+
fields = ["alpha", "A", "theta", "D", "sigma", "offset", "m", "Jm", "G", "B", "convention"];
202+
203+
def __setattr__(self, name, value):
204+
"""
205+
Set attributes of the Link object
206+
207+
- alpha; scalar
208+
- A; scalar
209+
- theta; scalar
210+
- D; scalar
211+
- sigma; scalar
212+
- offset; scalar
213+
- m; scalar
214+
- Jm; scalar
215+
- G; scalar
216+
- B; scalar
217+
- r; 3-vector
218+
- I; 3x3 matrix, 3-vector or 6-vector
219+
- Tc; scalar or 2-vector
220+
- qlim; 2-vector
221+
222+
Inertia, I, can be specified as:
223+
- 3x3 inertia tensor
224+
- 3-vector, the diagonal of the inertia tensor
225+
- 6-vector, the unique elements of the inertia tensor [Ixx Iyy Izz Ixy Iyz Ixz]
226+
227+
Coloumb friction, Tc, can be specifed as:
228+
- scalar, for the symmetric case when Tc- = Tc+
229+
- 2-vector, the assymetric case [Tc- Tc+]
230+
231+
Joint angle limits, qlim, is a 2-vector giving the lower and upper limits
232+
of motion.
233+
"""
234+
235+
if value == None:
236+
self.__dict__[name] = value;
237+
return;
238+
239+
if name in self.fields:
240+
# scalar parameter
241+
if isinstance(value, (ndarray,matrix)) and value.shape != (1,1):
242+
raise ValueError, "Scalar required"
243+
if not isinstance(value, (int,float,int32,float64)):
244+
raise ValueError;
245+
self.__dict__[name] = value
246+
247+
elif name == "r":
248+
r = arg2array(value);
249+
if len(r) != 3:
250+
raise ValueError, "matrix required"
251+
252+
self.__dict__[name] = mat(r)
253+
254+
elif name == "I":
255+
if isinstance(value, matrix) and value.shape == (3,3):
256+
self.__dict__[name] = value;
257+
else:
258+
v = arg2array(value);
259+
if len(v) == 3:
260+
self.__dict__[name] = mat(diag(v))
261+
elif len(v) == 6:
262+
self.__dict__[name] = mat([
263+
[v[0],v[3],v[5]],
264+
[v[3],v[1],v[4]],
265+
[v[5],v[4],v[2]]])
266+
else:
267+
raise ValueError, "matrix required";
268+
269+
elif name == "Tc":
270+
v = arg2array(value)
271+
272+
if len(v) == 1:
273+
self.__dict__[name] = mat([-v[0], v[0]])
274+
elif len(v) == 2:
275+
self.__dict__[name] = mat(v)
276+
else:
277+
raise ValueError;
278+
279+
elif name == "qlim":
280+
v = arg2array(value);
281+
if len(v) == 2:
282+
self.__dict__[name] = mat(v);
283+
else:
284+
raise ValueError
285+
else:
286+
raise NameError, "Unknown attribute <%s> of link" % name
287+
288+
289+
# LINK.islimit(q) return if limit is exceeded: -1, 0, +1
290+
def islimit(self,q):
291+
"""
292+
Check if joint limits exceeded. Returns
293+
- -1 if C{q} is less than the lower limit
294+
- 0 if C{q} is within the limits
295+
- +1 if C{q} is greater than the high limit
296+
297+
@type q: number
298+
@param q: Joint coordinate
299+
@rtype: -1, 0, +1
300+
@return: joint limit status
301+
"""
302+
if not self.qlim:
303+
return 0
304+
305+
return (q > self.qlim[1,0]) - (q < self.qlim[0,0])
306+
307+
def tr(self, q):
308+
"""
309+
Compute the transformation matrix for this link. This is a function
310+
of kinematic parameters, the kinematic model (DH or MDH) and the joint
311+
coordinate C{q}.
312+
313+
@type q: number
314+
@param q: joint coordinate
315+
@rtype: homogeneous transformation
316+
@return: Link transform M{A(q)}
317+
"""
318+
319+
an = self.A
320+
dn = self.D
321+
theta = self.theta
322+
323+
if self.sigma == 0:
324+
theta = q # revolute
325+
else:
326+
dn = q # prismatic
327+
328+
sa = sin(self.alpha); ca = cos(self.alpha);
329+
st = sin(theta); ct = cos(theta);
330+
331+
if self.convention == Link.LINK_DH:
332+
# standard
333+
t = mat([[ ct, -st*ca, st*sa, an*ct],
334+
[st, ct*ca, -ct*sa, an*st],
335+
[0, sa, ca, dn],
336+
[0, 0, 0, 1]]);
337+
338+
else:
339+
# modified
340+
t = mat([[ ct, -st, 0, an],
341+
[st*ca, ct*ca, -sa, -sa*dn],
342+
[st*sa, ct*sa, ca, ca*dn],
343+
[0, 0, 0, 1]]);
344+
345+
return t;
File renamed without changes.
File renamed without changes.
File renamed without changes.

0 commit comments

Comments
 (0)
pFad - Phonifier reborn

Pfad - The Proxy pFad of © 2024 Garber Painting. All rights reserved.

Note: This service is not intended for secure transactions such as banking, social media, email, or purchasing. Use at your own risk. We assume no liability whatsoever for broken pages.


Alternative Proxies:

Alternative Proxy

pFad Proxy

pFad v3 Proxy

pFad v4 Proxy