8000 fixed r urdf · yobzhuu/robotics-toolbox-python@8fcb457 · GitHub
[go: up one dir, main page]

Skip to content

Commit 8fcb457

Browse files
committed
fixed r urdf
1 parent 6c533ef commit 8fcb457

File tree

7 files changed

+45
-19
lines changed

7 files changed

+45
-19
lines changed

examples/test.py

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
#!/usr/bin/env python
2+
"""
3+
@author Jesse Haviland
4+
"""
5+
6+
import roboticstoolbox as rtb
7+
import spatialmath as sm
8+
import numpy as np
9+
import qpsolvers as qp
10+
import time
11+
12+
# Launch the simulator Swift
13+
env = rtb.backend.Swift()
14+
env.launch()
15+
16+
# Create a Panda robot object
17+
puma = rtb.models.Puma560()
18+
19+
# Set joint angles to ready configuration
20+
puma.q = puma.qr
21+
22+
# Add the puma to the simulator
23+
env.add(puma)

roboticstoolbox/backend/Swift/Swift.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ class Swift(Connector): # pragma nocover
3838
:references:
3939
4040
- https://github.com/jhavl/swift
41-
41+
4242
"""
4343
def __init__(self):
4444
super(Swift, self).__init__()
@@ -72,11 +72,11 @@ def step(self, dt=50):
7272
7373
:param dt: time step in milliseconds, defaults to 50
7474
:type dt: int, optional
75-
75+
7676
``env.step(args)`` triggers an update of the 3D scene in the Swift
7777
window referenced by ``env``.
7878
79-
.. note::
79+
.. note::
8080
8181
- Each robot in the scene is updated based on
8282
their control type (position, velocity, acceleration, or torque).
@@ -89,7 +89,7 @@ def step(self, dt=50):
8989
"""
9090

9191
# TODO how is the pose of shapes updated prior to step?
92-
92+
9393
super().step
9494

9595
self._step_robots(dt)

roboticstoolbox/backend/urdf/urdf.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1744,7 +1744,7 @@ def __init__(self, name, links, joints=None,
17441744
# Store the visuals, collisions, and inertials
17451745
for i in range(len(joints)):
17461746
link = self._link_map[joints[i].child]
1747-
elinks[i].r = link.inertial.origin
1747+
elinks[i].r = link.inertial.origin[:3, 3]
17481748
elinks[i].m = link.inertial.mass
17491749
elinks[i].inertia = link.inertial.inertia
17501750

roboticstoolbox/robot/DHDynamics.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1427,7 +1427,7 @@ def _cross(a, b):
14271427
a[0] * b[1] - a[1] * b[0]]
14281428

14291429

1430-
if __name__ == "__main__":
1430+
if __name__ == "__main__": # pragma nocover
14311431

14321432
import roboticstoolbox as rtb
14331433
# from spatialmath.base import symbolic as sym

roboticstoolbox/robot/ERobot.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -265,7 +265,7 @@ def urdf_to_ets_args(self, file_path, tld=None):
265265
# get the path to the class that defines the robot
266266
classpath = sys.modules[self.__module__].__file__
267267
# add on relative path to get to the URDF or xacro file
268-
base_path = PurePath(classpath).parent.parent / 'xacro'
268+
base_path = PurePath(classpath).parent.parent / 'xacro'
269269
file_path = base_path / PurePosixPath(file_path)
270270
name, ext = splitext(file_path)
271271

roboticstoolbox/robot/Link.py

Lines changed: 14 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
from spatialmath.base.argcheck import getvector, \
55
isscalar, isvector, ismatrix
66

7+
78
def _listen_dyn(func):
89
@wraps(func)
910
def wrap F438 per_listen_dyn(*args):
@@ -12,9 +13,11 @@ def wrapper_listen_dyn(*args):
1213
return func(*args)
1314
return wrapper_listen_dyn
1415

16+
1517
class Link:
1618

17-
def __init__(self,
19+
def __init__(
20+
self,
1821
name='',
1922
offset=0.0,
2023
qlim=np.zeros(2),
@@ -49,7 +52,6 @@ def __init__(self,
4952
self.Tc = Tc
5053
self.G = G
5154

52-
5355
def copy(self):
5456
"""
5557
Copy of link object
@@ -278,7 +280,7 @@ def flip(self):
278280
- ``link.flip = ...`` checks and sets the joint flip status
279281
280282
Joint flip defines the direction of motion of the joint.
281-
283+
282284
``flip = False`` is conventional motion direction:
283285
284286
- revolute motion is a positive rotation about the z-axis
@@ -350,12 +352,12 @@ def I(self): # noqa
350352
:rtype: ndarray(3,3)
351353
- ``link.I = ...`` checks and sets the link inertia
352354
353-
Link inertia is a symmetric 3x3 matrix describing the inertia with respect
354-
to a frame with its origin at the centre of mass, and with axes parallel to those of
355-
the link frame.
355+
Link inertia is a symmetric 3x3 matrix describing the inertia with
356+
respect to a frame with its origin at the centre of mass, and with
357+
axes parallel to those of the link frame.
356358
357359
The inertia matrix is
358-
360+
359361
.. math::
360362
361363
\begin{bmatrix} I_{xx} & I_{xy} & I_{xz} \\
@@ -435,7 +437,8 @@ def B(self):
435437
:rtype: float
436438
- ``link.B = ...`` checks and sets the motor viscous friction
437439
438-
.. note:: Viscous friction is the same for positive and negative motion.
440+
.. note:: Viscous friction is the same for positive and negative
441+
motion.
439442
"""
440443
return self._B
441444

@@ -455,7 +458,7 @@ def Tc(self):
455458
Get/set motor Coulomb friction
456459
457460
- ``link.Tc`` is the motor Coulomb friction
458-
:return: motor Coulomb friction
461+
:return: motor Coulomb friction
459462
:rtype: ndarray(2)
460463
- ``link.Tc = ...`` checks and sets the motor Coulomb friction. If a
461464
scalar is given the value is set to [T, -T], if a 2-vector it is
@@ -470,7 +473,8 @@ def Tc(self):
470473
\tau_C^+ & \mbox{if $\dot{q} > 0$} \\
471474
\tau_C^- & \mbox{if $\dot{q} < 0$} \end{array} \right.
472475
473-
.. note:: :math:`\tau_C^+` must be :math:`> 0`, and :math:`\tau_C^-` must be :math:`< 0`.
476+
.. note:: :math:`\tau_C^+` must be :math:`> 0`, and :math:`\tau_C^-`
477+
must be :math:`< 0`.
474478
"""
475479
return self._Tc
476480

@@ -513,4 +517,3 @@ def G(self):
513517
@_listen_dyn
514518
def G(self, G_new):
515519
self._G = G_new
516-

tests/test_ELink.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -160,7 +160,7 @@ def test_properties(self):
160160
l0 = rp.ELink()
161161

162162
self.assertEqual(l0.m, 0.0)
163-
nt.assert_array_almost_equal(l0.r.A, np.eye(4))
163+
nt.assert_array_almost_equal(l0.r, np.zeros(3))
164164
self.assertEqual(l0.Jm, 0.0)
165165

166166
def test_fail_parent(self):

0 commit comments

Comments
 (0)
0