Skip to content

Commit b02f249

Browse files
committed
lgtm issues
1 parent c9773e4 commit b02f249

34 files changed

+132
-276
lines changed

examples/VPython.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
"""
55

66
import roboticstoolbox as rp
7-
import time
7+
# import time
88

99
env = rp.backend.VPython()
1010
env.launch()

roboticstoolbox/backend/Dynamixel/dynamixel_sdk/protocol1_packet_handler.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ def txPacket(self, port, txpacket):
130130
def rxPacket(self, port):
131131
rxpacket = []
132132

133-
result = COMM_TX_FAIL
133+
result = COMM_TX_FAIL # lgtm [py/multiple-definition]
134134
checksum = 0
135135
rx_length = 0
136136
wait_length = 6 # minimum length (HEADER0 HEADER1 ID LENGTH ERROR CHKSUM)
@@ -310,7 +310,7 @@ def readTx(self, port, dxl_id, address, length):
310310
return result
311311

312312
def readRx(self, port, dxl_id, length):
313-
result = COMM_TX_FAIL
313+
result = COMM_TX_FAIL # lgtm [py/multiple-definition]
314314
error = 0
315315

316316
rxpacket = None

roboticstoolbox/backend/Dynamixel/dynamixel_sdk/protocol2_packet_handler.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -249,7 +249,7 @@ def txPacket(self, port, txpacket):
249249
def rxPacket(self, port):
250250
rxpacket = []
251251

252-
result = COMM_TX_FAIL
252+
result = COMM_TX_FAIL # lgtm [py/multiple-definition]
253253
rx_length = 0
254254
wait_length = 11 # minimum length (HEADER0 HEADER1 HEADER2 RESERVED ID LENGTH_L LENGTH_H INST ERROR CRC16_L CRC16_H)
255255

@@ -438,7 +438,7 @@ def broadcastPing(self, port):
438438
return data_list, result
439439

440440
else:
441-
result = COMM_RX_CORRUPT
441+
result = COMM_RX_CORRUPT # lgtm [py/multiple-definition]
442442

443443
# remove header (0xFF 0xFF 0xFD)
444444
del rxpacket[0: 3]
@@ -450,7 +450,7 @@ def broadcastPing(self, port):
450450
rx_length = rx_length - idx
451451

452452
# FIXME: unreachable code
453-
return data_list, result
453+
return data_list, result # lgtm [py/unreachable-statement]
454454

455455
def action(self, port, dxl_id):
456456
txpacket = [0] * 10
@@ -526,7 +526,7 @@ def readTx(self, port, dxl_id, address, length):
526526
return result
527527

528528
def readRx(self, port, dxl_id, length):
529-
result = COMM_TX_FAIL
529+
result = COMM_TX_FAIL # lgtm [py/multiple-definition]
530530
error = 0
531531

532532
rxpacket = None

roboticstoolbox/backend/VPython/VPython.py

Lines changed: 33 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -3,17 +3,41 @@
33
@author Micah Huth
44
"""
55

6+
import importlib
67
from roboticstoolbox.backend.Connector import Connector
7-
88
from roboticstoolbox.robot.DHLink import DHLink
99
from roboticstoolbox.robot.Robot import Robot as r
1010

11-
from roboticstoolbox.backend.VPython.canvas import GraphicsCanvas3D, \
12-
GraphicsCanvas2D
13-
from roboticstoolbox.backend.VPython.graphicalrobot import \
14-
GraphicalRobot
15-
from roboticstoolbox.backend.VPython.common_functions import \
16-
close_localhost_session
11+
GraphicsCanvas3D = None
12+
GraphicsCanvas2D = None
13+
GraphicalRobot = None
14+
close_localhost_session = None
15+
16+
17+
def _imports():
18+
global GraphicsCanvas3D
19+
global GraphicsCanvas2D
20+
global GraphicalRobot
21+
global close_localhost_session
22+
23+
try:
24+
canvas = importlib.import_module(
25+
'roboticstoolbox.backend.VPython.canvas')
26+
GraphicsCanvas3D = canvas.GraphicsCanvas3D
27+
GraphicsCanvas2D = canvas.GraphicsCanvas2D
28+
29+
graphicalrobot = importlib.import_module(
30+
'roboticstoolbox.backend.VPython.graphicalrobot')
31+
GraphicalRobot = graphicalrobot.GraphicalRobot
32+
33+
common_functions = importlib.import_module(
34+
'roboticstoolbox.backend.VPython.common_functions')
35+
close_localhost_session = common_functions.close_localhost_session
36+
37+
except ImportError:
38+
print(
39+
'\nYou must install the VPython component of the toolbox, do: \n'
40+
'pip install roboticstoolbox[vpython]\n\n')
1741

1842

1943
class VPython(Connector): # pragma nocover
@@ -54,6 +78,8 @@ def __init__(self):
5478
"""
5579
super(VPython, self).__init__()
5680

81+
_imports()
82+
5783
# Init vars
5884
self.canvases = []
5985
# 2D array of [is_3d, height, width, title, caption, grid] per canvas

roboticstoolbox/backend/VPython/stl.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@
1010

1111
try:
1212
from roboticstoolbox.tools.stdout_supress import pipes
13-
except BaseException: # pragma nocover
13+
except Exception: # pragma nocover
1414
from contextlib import contextmanager
1515

1616
@contextmanager
@@ -22,7 +22,7 @@ def pipes(stdout=None, stderr=None):
2222
try:
2323
with pipes(stdout=_out, stderr=_err):
2424
from stl import mesh
25-
except BaseException: # pragma nocover
25+
except Exception: # pragma nocover
2626
from stl import mesh
2727

2828

roboticstoolbox/backend/urdf/tests/test_urdf.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ def test_urdf_visuals(self):
7474

7575
try:
7676
xacro.main("")
77-
except BaseException:
77+
except BaseException: # lgtm [py/catch-base-exception]
7878
pass
7979

8080
def test_urdf_load(self):
@@ -84,7 +84,7 @@ def test_urdf_load(self):
8484

8585
try:
8686
xacro.main("")
87-
except BaseException:
87+
except BaseException: # lgtm [py/catch-base-exception]
8888
pass
8989

9090
def test_urdf_collisions(self):
@@ -105,7 +105,7 @@ def test_urdf_collisions(self):
105105

106106
try:
107107
xacro.main("")
108-
except BaseException:
108+
except BaseException: # lgtm [py/catch-base-exception]
109109
pass
110110

111111
def test_urdf_dynamics(self):
@@ -121,5 +121,5 @@ def test_urdf_dynamics(self):
121121

122122
try:
123123
xacro.main("")
124-
except BaseException:
124+
except BaseException: # lgtm [py/catch-base-exception]
125125
pass

roboticstoolbox/backend/urdf/urdf.py

Lines changed: 5 additions & 136 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,6 @@
55
"""
66

77
import numpy as np
8-
from spatialmath import base
98
import roboticstoolbox as rtb
109
import copy
1110
import os
@@ -1612,7 +1611,7 @@ def __init__(self, name, links, joints=None,
16121611
# why arent the other things validated
16131612
try:
16141613
self._validate_transmissions()
1615-
except BaseException:
1614+
except Exception:
16161615
pass
16171616

16181617
self.name = name
@@ -1711,18 +1710,18 @@ def __init__(self, name, links, joints=None,
17111710

17121711
# joint limit
17131712
try:
1714-
qlim = [joint.limit.lower, joint.limit.upper]
1713+
joint.qlim = [joint.limit.lower, joint.limit.upper]
17151714
except AttributeError:
17161715
# no joint limits provided
1717-
qlim = None
1716+
pass
17181717

17191718
# joint friction
17201719
try:
17211720
if joint.dynamics.friction is not None:
17221721
childlink.B = joint.dynamics.friction
17231722

17241723
# TODO Add damping
1725-
joint.dynamics.damping
1724+
# joint.dynamics.damping
17261725
except AttributeError:
17271726
pass
17281727

@@ -1737,136 +1736,6 @@ def __init__(self, name, links, joints=None,
17371736
# TODO, why did you put the base_link on the end?
17381737
# easy to do it here
17391738

1740-
# for i in range(len(elinks)):
1741-
# found = False
1742-
# for joint in range(len(elinks)):
1743-
# if i != joint:
1744-
# if self.joints[i].parent == self.joints[joint].child:
1745-
# elinks[i]._parent = elinks[joint]
1746-
# found = True
1747-
1748-
# if not found:
1749-
# link = self._link_map[self.joints[i].parent]
1750-
# base_link = rtb.ELink(
1751-
# rtb.ETS(),
1752-
# name=link.name)
1753-
# elinks[i]._parent = base_link
1754-
# try:
1755-
# for visual in link.visuals:
1756-
# base_link.geometry.append(visual.geometry.ob)
1757-
# except AttributeError: # pragma nocover
1758-
# pass
1759-
1760-
# for joint in self.joints:
1761-
# # each joint has a reference to a parent and child link
1762-
1763-
# ets = rtb.ETS()
1764-
# T = sm.SE3(joint.origin)
1765-
# trans = T.t
1766-
# rot = joint.rpy
1767-
# var = None
1768-
1769-
# ets = ETS.SE3(trans, rot)
1770-
# # if trans[0] != 0:
1771-
# # ets = ets * rtb.ETS.tx(trans[0])
1772-
1773-
# # if trans[1] != 0:
1774-
# # ets = ets * rtb.ETS.ty(trans[1])
1775-
1776-
# # if trans[2] != 0:
1777-
# # ets = ets * rtb.ETS.tz(trans[2])
1778-
1779-
# # if rot[0] != 0:
1780-
# # ets = ets * rtb.ETS.rx(rot[0])
1781-
1782-
# # if rot[1] != 0:
1783-
# # ets = ets * rtb.ETS.ry(rot[1])
1784-
1785-
# # if rot[2] != 0:
1786-
# # ets = ets * rtb.ETS.rz(rot[2])
1787-
1788-
# if joint.joint_type == 'revolute' or \
1789-
# joint.joint_type == 'continuous': # pragma nocover
1790-
# if joint.axis[0] == 1:
1791-
# var = rtb.ETS.rx()
1792-
# elif joint.axis[0] == -1:
1793-
# var = rtb.ETS.rx(flip=True)
1794-
# elif joint.axis[1] == 1:
1795-
# var = rtb.ETS.ry()
1796-
# elif joint.axis[1] == -1:
1797-
# var = rtb.ETS.ry(flip=True)
1798-
# elif joint.axis[2] == 1:
1799-
# var = rtb.ETS.rz()
1800-
# elif joint.axis[2] == -1:
1801-
# var = rtb.ETS.rz(flip=True)
1802-
# elif joint.joint_type == 'prismatic': # pragma nocover
1803-
# if joint.axis[0] == 1:
1804-
# var = rtb.ETS.tx()
1805-
# elif joint.axis[0] == -1:
1806-
# var = rtb.ETS.tx(flip=True)
1807-
# elif joint.axis[1] == 1:
1808-
# var = rtb.ETS.ty()
1809-
# elif joint.axis[1] == -1:
1810-
# var = rtb.ETS.ty(flip=True)
1811-
# elif joint.axis[2] == 1:
1812-
# var = rtb.ETS.tz()
1813-
# elif joint.axis[2] == -1:
1814-
# var = rtb.ETS.tz(flip=True)
1815-
1816-
# try:
1817-
# qlim = [joint.limit.lower, joint.limit.upper]
1818-
# except AttributeError:
1819-
# qlim = [0, 0]
1820-
1821-
# elinks.append(
1822-
# rtb.ELink(
1823-
# ets,
1824-
# var,
1825-
# name=joint.name,
1826-
# qlim=qlim
1827-
# )
1828-
# )
1829-
# elinks_dict[elinks[-1].name] = elinks[-1]
1830-
1831-
# elinks.append(base_link)
1832-
# self.elinks = elinks
1833-
1834-
# Store the visuals, collisions, and inertials
1835-
# for i in range(len(joints)):
1836-
# link = self._link_map[joints[i].child]
1837-
# elinks[i].r = link.inertial.origin[:3, 3]
1838-
# elinks[i].m = link.inertial.mass
1839-
# elinks[i].inertia = link.inertial.inertia
1840-
1841-
# try:
1842-
# if self.joints[i].dynamics.friction is not None:
1843-
# elinks[i].B = self.joints[i].dynamics.friction
1844-
1845-
# # TODO Add damping
1846-
# self.joints[i].dynamics.damping
1847-
# except AttributeError:
1848-
# pass
1849-
1850-
# try:
1851-
# for visual in link.visuals:
1852-
# elinks[i].geometry.append(visual.geometry.ob)
1853-
# except AttributeError: # pragma nocover
1854-
# pass
1855-
1856-
# try:
1857-
# colls = []
1858-
# for col in link.collisions:
1859-
# colls.append(col.geometry.ob)
1860-
# elinks[i].collision = colls
1861-
# except AttributeError: # pragma nocover
1862-
# pass
1863-
1864-
# # Apply gear ratio
1865-
# self._validate_transmissions()
1866-
# for t in self.transmissions:
1867-
# elinks_dict[self.joint_map[t.joints[0].name].name].G = \
1868-
# t.actuators[0].mechanicalReduction
1869-
18701739
@property
18711740
def name(self):
18721741
"""str : The name of the URDF.
@@ -2003,7 +1872,7 @@ def loadstr(str_obj, file_obj):
20031872
path, _ = os.path.split(file_obj)
20041873

20051874
else: # pragma nocover
2006-
parser = ET.XMLParser(remove_comments=True, remove_blank_text=True)
1875+
parser = ET.XMLParser()
20071876
tree = ET.parse(file_obj, parser=parser)
20081877
path, _ = os.path.split(file_obj.name)
20091878

roboticstoolbox/models/URDF/Mico.py

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -2,16 +2,14 @@
22

33
import numpy as np
44
from roboticstoolbox.robot.ERobot import ERobot
5-
from pathlib import Path
6-
import roboticstoolbox as rp
75

86

97
class Mico(ERobot):
108
"""
119
Class that imports a Mico URDF model
1210
1311
``Panda()`` is a class which imports a Kinova Mico robot definition
14-
from a URDF file. The model describes its kinematic and graphical
12+
from a URDF file. The model describes its kinematic and graphical
1513
characteristics.
1614
1715
.. runblock:: pycon
@@ -47,5 +45,5 @@ def __init__(self):
4745

4846
if __name__ == '__main__': # pragma nocover
4947

50-
robot = j2n4s300()
48+
robot = Mico()
5149
print(robot)

roboticstoolbox/models/URDF/PR2.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,6 @@
11
#!/usr/bin/env python
22

3-
import roboticstoolbox as rp
43
from roboticstoolbox.robot.ERobot import ERobot
5-
from pathlib import Path
64

75

86
class PR2(ERobot):

roboticstoolbox/models/URDF/Panda.py

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

33
import numpy as np
4-
import roboticstoolbox as rp
54
from roboticstoolbox.robot.ERobot import ERobot
65

76

0 commit comments

Comments
 (0)