8000 make add, step methods have similar arguments to other backends · yobzhuu/robotics-toolbox-python@922c982 · GitHub
[go: up one dir, main page]

Skip to content

Commit 922c982

Browse files
committed
make add, step methods have similar arguments to other backends
fix circular import
1 parent a55b4b8 commit 922c982

File tree

2 files changed

+54
-30
lines changed

2 files changed

+54
-30
lines changed

roboticstoolbox/backends/VPython/VPython.py

Lines changed: 53 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,10 @@
1414
from roboticstoolbox.backends.Connector import Connector
1515
# from roboticstoolbox.robot.DHLink import DHLink
1616
# from roboticstoolbox.robot.Robot import Robot as r
17-
from roboticstoolbox import DHLink, DHRobot
17+
# from roboticstoolbox.robot import DHLink, DHRobot
18+
19+
# from roboticstoolbox.robot.DHRobot import DHRobot
20+
# from roboticstoolbox.robot.DHLink import DHLink
1821

1922
GraphicsCanvas3D = None
2023
GraphicsCanvas2D = None
@@ -79,7 +82,7 @@ class VPython(Connector): # pragma nocover
7982
# TODO be able to add ellipsoids (vellipse, fellipse)
8083
# TODO be able add lines (for end-effector paths)
8184

82-
def __init__(self):
85+
def __init__(self, **kwargs):
8386
"""
8487
Open a localhost session with no canvases
8588
@@ -98,12 +101,12 @@ def __init__(self):
98101
self._recording_fps = None
99102
self._thread_lock = threading.Lock()
100103

104+
self.launch_options = kwargs # save launch options
105+
101106
self._create_empty_session()
102107

103108
def launch(
104-
self, is_3d=True, height=500, width=888,
105-
title='', caption='', grid=True,
106-
g_col=None):
109+
self, **kwargs):
107110
"""
108111
Launch a graphical backend in a browser tab
109112
@@ -112,6 +115,16 @@ def launch(
112115
113116
"""
114117

118+
# merge instantiation & launch options
119+
args = {**self.launch_options, **kwargs}
120+
is_3d = args.get('is_3d', True)
121+
height = args.get('height', 500)
122+
width = args.get('width', 888)
123+
title = args.get('title', 'Robotics Toolbox for Python: VPython display')
124+
caption = args.get('caption', '')
125+
grid = args.get('grid', False)
126+
g_col = args.get('g_col', None)
127+
115128
super().launch()
116129

117130
self.canvas_settings.append(
@@ -127,11 +140,11 @@ def launch(
127140
GraphicsCanvas2D(height, width, title, caption,
128141
grid, g_col))
129142

130-
def step(self, id, q=None, fig_num=0):
143+
def step(self, dt=None, id=None, q=None, fig_num=0):
131144
"""
132145
Update the graphical scene
133146
134-
:param id: The Identification of the robot to remove. Can be either the
147+
:param id: The Identification of the robot to move. Can be either the
135148
DHRobot or GraphicalRobot
136149
:type id: :class:`~roboticstoolbox.robot.DHRobot.DHRobot`,
137150
:class:`roboticstoolbox.backends.VPython.graphics_robot.GraphicalRobot`
@@ -166,32 +179,40 @@ def step(self, id, q=None, fig_num=0):
166179
raise ValueError(
167180
"Figure number must be between 0 and total number of canvases")
168181

169-
# If DHRobot given
170-
if isinstance(id, DHRobot):
171-
robot = None
172-
# Find first occurrence of it that is in the correct canvas
173-
for i in range(len(self.robots)):
174-
if self.robots[i].robot is id and \
175-
self.canvases[fig_num].is_robot_in_canvas(
176-
self.robots[i]):
177-
robot = self.robots[i]
178-
break
182+
# If GraphicalRobot given
183+
if isinstance(id, GraphicalRobot):
184+
if self.canvases[fig_num].is_robot_in(id):
185+
poses = id.fkine(q)
186+
id.set_joint_poses(poses)
187+
188+
#if isinstance(id, DHRobot): # HACK avoid circular import
189+
else:
190+
# robot = None
191+
# # Find first occurrence of it that is in the correct canvas
192+
# for i in range(len(self.robots)):
193+
# if self.robots[i].robot is id and \
194+
# self.canvases[fig_num].is_robot_in_canvas(
195+
# self.robots[i]):
196+
# robot = self.robots[i]
197+
# break
198+
if id is None:
199+
robot = self.robots[0]
179200
if robot is None:
180201
print("No robot")
181202
return
182203
else:
183204
poses = robot.fkine(q)
184205
robot.set_joint_poses(poses)
185206
# ElseIf GraphicalRobot given
186-
elif isinstance(id, GraphicalRobot):
187-
if self.canvases[fig_num].is_robot_in(id):
188-
poses = id.fkine(q)
189-
id.set_joint_poses(poses)
190-
# Else
191-
else:
192-
raise TypeError(
193-
"Input must be a Robot (or subclass) or "
194-
"GraphicalRobot, given {0}".format(type(id)))
207+
208+
# # Else
209+
# else:
210+
# raise TypeError(
211+
# "Input must be a Robot (or subclass) or "
212+
# "GraphicalRobot, given {0}".format(type(id)))
213+
214+
if dt is not None:
215+
sleep(dt)
195216

196217
def reset(self):
197218
"""
@@ -265,16 +286,16 @@ def close(self):
265286

266287
self.canvases = []
267288

268-
def add(self, fig_num, name, dhrobot):
289+
def add(self, dhrobot, fig_num=0, name=None):
269290
"""
270291
Add a robot to the graphical scene
271292
293+
:param dhrobot: The ``DHRobot`` object (if applicable)
294+
:type dhrobot: class:`~roboticstoolbox.robot.DHRobot.DHRobot`, None
272295
:param fig_num: The canvas number to place the robot in
273296
:type fig_num: int
274297
:param name: The name of the robot
275298
:type name: `str`
276-
:param dhrobot: The ``DHRobot`` object (if applicable)
277-
:type dhrobot: class:`~roboticstoolbox.robot.DHRobot.DHRobot`, None
278299
:raises ValueError: Figure number must be between 0 and number of
279300
figures created
280301
:return: object id within visualizer
@@ -306,6 +327,9 @@ def add(self, fig_num, name, dhrobot):
306327

307328
super().add()
308329

330+
if name is None:
331+
name = dhrobot.name
332+
309333
# Sanity check input
310334
if fig_num < 0 or fig_num > len(self.canvases) - 1:
311335
raise ValueError(

roboticstoolbox/backends/VPython/grid.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -127,7 +127,7 @@ def __create_grid_objects(self):
127127

128128
# As curve objects cannot be compounded, so must be a single entity
129129

130-
line_thickness = min(max(self.__scale / 25, 0.01), 5) # 0.01 -> 5
130+
line_thickness = min(max(self.__scale / 25, 0.01), 2) # 0.01 -> 5
131131

132132
# Update curve objects
133133
self.grid_object.get('xy_plane').radius = line_thickness

0 commit comments

Comments
 (0)
0