Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[python/viewer] Fix some edge-cases with panda3d backend. #673

Merged
merged 1 commit into from
Dec 11, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
4 changes: 4 additions & 0 deletions python/gym_jiminy/rllib/gym_jiminy/rllib/utilities.py
Original file line number Diff line number Diff line change
Expand Up @@ -1067,6 +1067,10 @@ def evaluate_algo(algo: Algorithm,
shutil.move(all_log_paths[idx], log_path)
log_paths.append(log_path)

# Make sure there is no viewer already open at this point.
# Otherwise adding the legend will fail.
Viewer.close()

# Replay and/or record a video of the best and worst trials if requested.
# Async to enable replaying and recording while training keeps going.
viewer_kwargs, *_ = chain(*eval_workers.foreach_env(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@
WIDGET_MARGIN_REL = 0.02

PANDA3D_FRAMERATE_MAX = 40
PANDA3D_REQUEST_TIMEOUT = 30.0


Tuple3FType = Union[Tuple[float, float, float], np.ndarray]
Expand Down Expand Up @@ -1530,6 +1531,7 @@ def set_material(self,
if texture_path:
texture = self.loader.load_texture(texture_path)
node.set_texture(texture)
node.set_transparency(TransparencyAttrib.M_alpha)

def set_scale(self,
root_path: str,
Expand Down Expand Up @@ -1856,7 +1858,7 @@ def __getattr__(self, name: str) -> Callable[..., Any]:
@wraps(getattr(Panda3dApp, name))
def _send(*args: Any, **kwargs: Any) -> Any:
if self._host_conn.closed:
raise ViewerError("Viewer not available anymore.")
raise ViewerClosedError("Viewer not available anymore.")
while self._host_conn.poll():
try:
reply = self._host_conn.recv()
Expand All @@ -1872,12 +1874,14 @@ def _send(*args: Any, **kwargs: Any) -> Any:
self._host_conn.send((name, args, kwargs, self._is_async))
if self._is_async:
return None
if self._host_conn.poll(10.0):
if self._host_conn.poll(PANDA3D_REQUEST_TIMEOUT):
reply = self._host_conn.recv()
else:
# Something is wrong... aborting to prevent potential deadlock
self._host_conn.send(("stop", (), (), True))
self._host_conn.close()
raise ViewerError("Viewer not available anymore.")
raise ViewerClosedError(
"Viewer has been because it did not respond.")
if isinstance(reply, Exception):
if isinstance(reply, ViewerClosedError):
# Close pipe to make sure it is not used in future
Expand Down
41 changes: 27 additions & 14 deletions python/jiminy_py/src/jiminy_py/viewer/viewer.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@

import numpy as np

from panda3d_viewer.viewer_errors import ViewerClosedError
from panda3d_viewer.viewer_errors import ViewerError, ViewerClosedError
try:
from psutil import Process
except ImportError:
Expand Down Expand Up @@ -552,7 +552,6 @@ def __init__(self, # pylint: disable=unused-argument
raise ValueError(
"Robot name already exists but must be unique. Please choose "
"a different one, or close the associated viewer.")
Viewer._backend_robot_names.add(robot_name)

# Enforce some arguments based on available features
if not backend.startswith('panda3d'):
Expand Down Expand Up @@ -598,6 +597,7 @@ def __init__(self, # pylint: disable=unused-argument
prefix="_".join((Viewer.window_name, scene_name, robot_name, "")))

# Access the current backend or create one if none is available
self._client = None
self.__is_open = False
self.is_backend_parent = not Viewer.is_alive()
try:
Expand Down Expand Up @@ -643,6 +643,8 @@ def __init__(self, # pylint: disable=unused-argument
"Impossible to create backend or connect to it.") from e

# Load the robot
Viewer._backend_robot_names.add(robot_name)
Viewer._backend_robot_colors[robot_name] = None
self._setup(robot, self.robot_color)

# Set default camera pose
Expand Down Expand Up @@ -688,15 +690,16 @@ def _setup(self,
assert Viewer.backend is not None

# Delete existing robot, if any
assert self.robot_name in Viewer._backend_robot_names
robot_node_path = '/'.join((self.scene_name, self.robot_name))
Viewer._delete_nodes_viewer([
'/'.join((robot_node_path, "visuals")),
'/'.join((robot_node_path, "collisions"))])

# Backup desired color
assert self.robot_name in Viewer._backend_robot_colors.keys()
self.robot_color = get_color_code(robot_color)
Viewer._backend_robot_colors.update({
self.robot_name: self.robot_color})
Viewer._backend_robot_colors[self.robot_name] = self.robot_color

# Create backend wrapper to get (almost) backend-independent API.
backend_type = get_backend_type(Viewer.backend)
Expand Down Expand Up @@ -1111,6 +1114,10 @@ def close(self: Optional[Union["Viewer", Type["Viewer"]]] = None) -> None:
Viewer._backend_proc = None
Viewer._has_gui = False
else:
# Consider that the robot is not available anymore, no matter what
Viewer._backend_robot_names.discard(self.robot_name)
Viewer._backend_robot_colors.pop(self.robot_name, None)

# Disable travelling if associated with this viewer instance
if (Viewer._camera_travelling is not None and
Viewer._camera_travelling['viewer'] is self):
Expand All @@ -1130,15 +1137,16 @@ def close(self: Optional[Union["Viewer", Type["Viewer"]]] = None) -> None:
if Viewer.backend == 'meshcat' and Viewer.is_alive():
Viewer._backend_obj.gui.window.zmq_socket.RCVTIMEO = 200

# Consider that the robot is not available anymore, no matter what
Viewer._backend_robot_names.discard(self.robot_name)
Viewer._backend_robot_colors.pop(self.robot_name, None)
# Delete robot from scene if requested
if (self.delete_robot_on_close and self._client is not None and
self.is_open()): # type: ignore[misc]
Viewer._delete_nodes_viewer([
self._client.visual_group,
self._client.collision_group,
self._markers_group])
self.is_open()): # type: ignore[unreachable]
try: # type: ignore[unreachable]
Viewer._delete_nodes_viewer([
self._client.visual_group,
self._client.collision_group,
self._markers_group])
except ViewerError:
pass

# Restore zmq socket timeout, which is disable by default
if Viewer.backend == 'meshcat':
Expand Down Expand Up @@ -1386,8 +1394,8 @@ def set_legend(labels: Optional[Sequence[str]] = None) -> None:
if labels is not None and (
len(labels) != len(Viewer._backend_robot_colors)):
raise RuntimeError(
f"Inconsistency between robots {Viewer._backend_robot_names}' "
f"and labels {labels}")
f"Inconsistency between robots {Viewer._backend_robot_names} "
f"({Viewer._backend_robot_colors}) and labels {labels}")

# Make sure all robots have a specific color
if any(color is None for color in Viewer._backend_robot_colors):
Expand Down Expand Up @@ -1762,6 +1770,7 @@ def set_color(self,
# Sanitize user-specified color code
color_ = get_color_code(color)

# Update the color of all the geometries of the robot
for model, geom_type in zip(
(self._client.visual_model, self._client.collision_model),
pin.GeometryType.names.values()):
Expand All @@ -1772,8 +1781,12 @@ def set_color(self,
color = geom.meshColor
self._gui.set_material(*node_name, color)

# Backup the new color
assert self.robot_name in Viewer._backend_robot_colors.keys()
self.robot_color = color_
Viewer._backend_robot_colors[self.robot_name] = color_

# Refresh the legend accordingly
Viewer._backend_obj.gui.set_legend()

@staticmethod
Expand Down