diff --git a/INSTALL.md b/INSTALL.md index 8fe0981bc..8b445c50f 100644 --- a/INSTALL.md +++ b/INSTALL.md @@ -6,25 +6,7 @@ #### Dependencies installation -There is not requirement to install `jiminy_py` on linux if one does not want to build it. Nevertheless, this package does not provide the backend viewer `gepetto-gui` (still, the backend `meshcat` is available). - -##### (optional) Gepetto viewer - -The first step to install `gepetto-gui` is to setup the APT repository `robotpkg` to have access to compiled binaries. - -```bash -sh -c "echo 'deb [arch=amd64] http://robotpkg.openrobots.org/packages/debian/pub bionic robotpkg' >> /etc/apt/sources.list.d/robotpkg.list" && \ -curl http://robotpkg.openrobots.org/packages/debian/robotpkg.key | sudo apt-key add - -apt update -``` - -Once done, it is straightforward to install the required package for Python 3.6. - -For Python 3.6 - -```bash -sudo apt install -y robotpkg-gepetto-viewer=4.4.0 robotpkg-py36-qt4-gepetto-viewer-corba=5.1.2 robotpkg-py36-omniorbpy -``` +There is no requirement to install `jiminy_py` on linux if one does not want to build it. #### Install Jiminy Python package diff --git a/build_tools/easy_install_deps_ubuntu.sh b/build_tools/easy_install_deps_ubuntu.sh index 6323c80d8..c742a14c2 100755 --- a/build_tools/easy_install_deps_ubuntu.sh +++ b/build_tools/easy_install_deps_ubuntu.sh @@ -81,8 +81,7 @@ fi # Note that `apt-get` is used instead of `apt` because it supports wildcard in package names apt-get install -y --allow-downgrades --allow-unauthenticated \ robotpkg-octomap=1.9.0 robotpkg-urdfdom-headers=1.0.4 robotpkg-hpp-fcl=1.7.1 robotpkg-pinocchio=2.5.6 \ - robotpkg-qt5-osgqt=3.5.7r2 robotpkg-py3*-qt5-gepetto-viewer=4.12.0r2 robotpkg-py3*-qt5-gepetto-viewer-corba=5.6.0 \ - robotpkg-py3*-omniorbpy=4.2.4 robotpkg-py3*-eigenpy=2.6.2 robotpkg-py3*-hpp-fcl=1.7.1 robotpkg-py3*-pinocchio=2.5.6 + robotpkg-py3*-eigenpy=2.6.2 robotpkg-py3*-hpp-fcl=1.7.1 robotpkg-py3*-pinocchio=2.5.6 # Add openrobots libraries to python packages search path if ! [ -f "${PYTHON_SITELIB}/openrobots.pth" ]; then diff --git a/examples/python/tutorial.ipynb b/examples/python/tutorial.ipynb index ae4062cb8..6ba72b63c 100644 --- a/examples/python/tutorial.ipynb +++ b/examples/python/tutorial.ipynb @@ -141,10 +141,10 @@ }, { "cell_type": "markdown", + "metadata": {}, "source": [ - "The results of a simulation can also be visualized in a 3D viewer: either `gepetto-gui` or `meshcat`. We use the latter here as it can be integrated in jupyter." - ], - "metadata": {} + "The results of a simulation can also be visualized in a 3D viewer: either `panda3d` or `meshcat`. We use the latter here as it can be integrated in jupyter." + ] }, { "cell_type": "code", diff --git a/python/jiminy_py/src/jiminy_py/core/__init__.py b/python/jiminy_py/src/jiminy_py/core/__init__.py index 745e1f454..9eb9df90c 100644 --- a/python/jiminy_py/src/jiminy_py/core/__init__.py +++ b/python/jiminy_py/src/jiminy_py/core/__init__.py @@ -58,7 +58,7 @@ _module = _importlib.import_module(".".join((__name__, module_name))) _sys.modules[module_name] = _module -# Register pinocchio_pywrap to avoid importing bindings twise, which messes up +# Register pinocchio_pywrap to avoid importing bindings twice, which messes up # with boost python converters. In addition, submodules search path needs to be # fixed for releases older than 2.5.6. submodules = _inspect.getmembers( @@ -82,10 +82,6 @@ __all__.append(name) attrib.__module__ = __name__ -# Patch Pinocchio to avoid loading ground geometry in viewer, and force -# `np.ndarray` type for from/to Python matrix converters. -from . import _pinocchio_init # noqa - # Define helpers to build extension modules def get_cmake_module_path(): diff --git a/python/jiminy_py/src/jiminy_py/core/_pinocchio_init.py b/python/jiminy_py/src/jiminy_py/core/_pinocchio_init.py deleted file mode 100644 index e5cc6cf3b..000000000 --- a/python/jiminy_py/src/jiminy_py/core/_pinocchio_init.py +++ /dev/null @@ -1,19 +0,0 @@ -import pinocchio as pin - - -# Use numpy array by default for Eigenpy and Pinocchio incidentally -__import__("eigenpy").switchToNumpyArray() - - -# Do not load the geometry of the ground is is not an actually geometry but -# rather a calculus artifact. -loadPrimitive_orig = \ - pin.visualize.gepetto_visualizer.GepettoVisualizer.loadPrimitive -def loadPrimitive(self, meshName, geometry_object): # noqa - if geometry_object.name == "ground": - return False - else: - return loadPrimitive_orig(self, meshName, geometry_object) - -pin.visualize.gepetto_visualizer.GepettoVisualizer.loadPrimitive = \ - loadPrimitive # noqa diff --git a/python/jiminy_py/src/jiminy_py/simulator.py b/python/jiminy_py/src/jiminy_py/simulator.py index a3590804c..1e28babc5 100644 --- a/python/jiminy_py/src/jiminy_py/simulator.py +++ b/python/jiminy_py/src/jiminy_py/simulator.py @@ -465,10 +465,6 @@ def render(self, """Render the current state of the simulation. One can display it or return an RGB array instead. - .. note:: - Gepetto-gui supports parallel rendering, which means that one can - display multiple simulations at the same time in different tabs. - :param return_rgb_array: Whether or not to return the current frame as an rgb array. :param width: Width of the returned RGB frame, if enabled. diff --git a/python/jiminy_py/src/jiminy_py/viewer/meshcat/index.html b/python/jiminy_py/src/jiminy_py/viewer/meshcat/index.html index 1b3b72430..5db761ce6 100644 --- a/python/jiminy_py/src/jiminy_py/viewer/meshcat/index.html +++ b/python/jiminy_py/src/jiminy_py/viewer/meshcat/index.html @@ -173,8 +173,7 @@ console.info("not connected to MeshCat server: ", e); } - // Replace the mesh grid by a filled checkerboard, similar to - // the one of Gepetto-gui. The paving size is 1m by 1m. + // Replace the mesh grid by tiles. The paving size is 1m by 1m. var segments = 20; var cmap = [new MeshCat.THREE.Color(0x222233), new MeshCat.THREE.Color(0xf2f2fe)]; var geometry = new MeshCat.THREE.PlaneBufferGeometry( @@ -199,8 +198,7 @@ viewer.scene_tree.find(["Axes", ""]).object.material.linewidth = 2.5 - // Update the "zoom" of the camera to match the behavior of - // Gepetto-gui, and update the default position of the camera. + // Update the "zoom" of the camera and its default position viewer.camera.fov = 30; viewer.camera.position.set(8.0, 1.2, 0); viewer.render(); diff --git a/python/jiminy_py/src/jiminy_py/viewer/replay.py b/python/jiminy_py/src/jiminy_py/viewer/replay.py index 4bb0cb1dd..bbadd5bb8 100644 --- a/python/jiminy_py/src/jiminy_py/viewer/replay.py +++ b/python/jiminy_py/src/jiminy_py/viewer/replay.py @@ -79,8 +79,8 @@ def play_trajectories(trajs_data: Union[ """Replay one or several robot trajectories in a viewer. The ratio between the replay and the simulation time is kept constant to - the desired ratio. One can choose between several backend (gepetto-gui or - meshcat). + the desired ratio. One can choose between several backend ('panda3d' or + 'meshcat'). .. note:: Replay speed is independent of the platform (windows, linux...) and @@ -172,9 +172,9 @@ def play_trajectories(trajs_data: Union[ input before starting to play the trajectories. Only available if `record_video_path` is None. Optional: False by default. - :param backend: Backend, one of 'panda3d', 'meshcat', or 'gepetto-gui'. If - `None`, the most appropriate backend will be selected - automatically, based on hardware and python environment. + :param backend: Backend, one of 'panda3d', 'meshcat'. If `None`, the most + appropriate backend will be selected automatically, based + on hardware and python environment. Optional: `None` by default. :param delete_robot_on_close: Whether or not to delete the robot from the viewer when closing it. @@ -690,7 +690,7 @@ def _play_logs_files_entrypoint() -> None: "assuming the robot has a freeflyer.")) parser.add_argument( '-b', '--backend', default='panda3d', - help="Display backend (panda3d, meshcat, or gepetto-gui).") + help="Display backend ('panda3d' or 'meshcat').") parser.add_argument( '-m', '--mesh_package_dir', default=None, help="Fullpath location of mesh package directory.") diff --git a/python/jiminy_py/src/jiminy_py/viewer/viewer.py b/python/jiminy_py/src/jiminy_py/viewer/viewer.py index f4be80eed..04176fc4e 100644 --- a/python/jiminy_py/src/jiminy_py/viewer/viewer.py +++ b/python/jiminy_py/src/jiminy_py/viewer/viewer.py @@ -13,7 +13,6 @@ import subprocess import webbrowser import multiprocessing -import xml.etree.ElementTree as ET from copy import deepcopy from urllib.request import urlopen from functools import wraps, partial @@ -32,15 +31,13 @@ from panda3d_viewer.viewer_errors import ViewerClosedError import pinocchio as pin -from pinocchio import SE3, SE3ToXYZQUAT, SE3ToXYZQUATtuple +from pinocchio import SE3, SE3ToXYZQUAT from pinocchio.rpy import rpyToMatrix, matrixToRpy -from pinocchio.visualize import GepettoVisualizer from .. import core as jiminy from ..core import (ContactSensor as contact, discretize_heightmap) from ..state import State -from ..dynamics import XYZQuatToXYZRPY from .meshcat.utilities import interactive_mode from .meshcat.wrapper import MeshcatWrapper from .meshcat.meshcat_visualizer import MeshcatVisualizer @@ -94,11 +91,6 @@ def filter(self, record): # Determine set the of available backends backends_available = {'meshcat': MeshcatVisualizer, 'panda3d': Panda3dVisualizer} -if sys.platform.startswith('linux'): - import importlib - if (importlib.util.find_spec("gepetto") is not None and - importlib.util.find_spec("omniORB") is not None): - backends_available['gepetto-gui'] = GepettoVisualizer try: from .panda3d.panda3d_widget import Panda3dQWidget backends_available['panda3d-qt'] = Panda3dVisualizer @@ -130,12 +122,6 @@ def _get_backend_exceptions( """ if backend is None: backend = default_backend() - if backend == 'gepetto-gui': - import gepetto - import omniORB - return (omniORB.CORBA.COMM_FAILURE, - omniORB.CORBA.TRANSIENT, - gepetto.corbaserver.gepetto.Error) elif backend.startswith('panda3d'): return (ViewerClosedError,) else: @@ -338,7 +324,7 @@ def __init__(self, `None` to use the unique lock of the current thread. Optional: `None` by default. :param backend: Name of the rendering backend to use. It can be either - 'panda3d', 'panda3d-qt', 'meshcat' or 'gepetto-gui'. + 'panda3d', 'panda3d-qt', 'meshcat'. None to keep using to one already running if any, or the default one otherwise. Note that the default is hardware and environment dependent. @@ -355,8 +341,7 @@ def __init__(self, Optional: False by default. :param robot_name: Unique robot name, to identify each robot. Optional: Randomly generated identifier by default. - :param scene_name: Scene name, used only with 'gepetto-gui' backend. It - must differ from the scene name. + :param scene_name: Scene name. Optional: 'world' by default. :param display_com: Whether or not to display the center of mass. Optional: Disabled by default. @@ -432,10 +417,7 @@ def __init__(self, else: backend = backend.lower() # Make sure backend's name is lowercase if backend not in backends_available: - if backend.startswith('gepetto'): - backend = 'gepetto-gui' - else: - raise ValueError("%s backend not available." % backend) + raise ValueError("%s backend not available." % backend) # Update the backend currently running, if any if Viewer.backend != backend and Viewer.is_alive(): @@ -451,11 +433,6 @@ def __init__(self, is_backend_running = True if not Viewer.is_open(): is_backend_running = False - if Viewer.backend == 'gepetto-gui': - try: - Viewer._backend_obj.gui.refresh() - except Viewer._backend_exceptions: - is_backend_running = False if not is_backend_running: Viewer._backend_obj = None Viewer._backend_proc = None @@ -604,18 +581,6 @@ def _setup(self, # Backup desired color self.robot_color = get_color_code(robot_color) - # Generate colorized URDF file if using gepetto-gui backend, since it - # is not supported by default, because of memory optimizations. - self.urdf_path = os.path.realpath(robot.urdf_path) - if Viewer.backend == 'gepetto-gui': - if self.robot_color is not None: - assert len(self.robot_color) == 4 - alpha = self.robot_color[3] - self.urdf_path = Viewer._get_colorized_urdf( - robot, self.robot_color[:3], self._tempdir) - else: - alpha = 1.0 - # Extract the right Pinocchio model if self.use_theoretical_model: pinocchio_model = robot.pinocchio_model_th @@ -636,36 +601,12 @@ def _setup(self, self._client.data = pinocchio_data self._client.collision_data = robot.collision_data - # Create the scene and load robot - if Viewer.backend == 'gepetto-gui': - # Initialize the viewer - self._client.initViewer(viewer=Viewer._backend_obj, - windowName=Viewer.window_name, - sceneName=self.scene_name, - loadModel=False) - - # Add missing scene elements - self._gui.addFloor('/'.join((self.scene_name, "floor"))) - self._gui.addLandmark(self.scene_name, 0.1) - - # Load the robot - self._client.loadViewerModel(rootNodeName=self.robot_name) - - # Set robot transparency - try: - self._gui.setFloatProperty(robot_node_path, 'Alpha', alpha) - except Viewer._backend_exceptions: - # Old Gepetto versions do no have 'Alpha' attribute but - # 'Transparency'. - self._gui.setFloatProperty( - robot_node_path, 'Transparency', 1 - alpha) - else: - # Initialize the viewer - self._client.initViewer(viewer=self._gui, loadModel=False) + # Initialize the viewer + self._client.initViewer(viewer=self._gui, loadModel=False) - # Load the robot - self._client.loadViewerModel( - rootNodeName=robot_node_path, color=self.robot_color) + # Create the scene and load robot + self._client.loadViewerModel( + rootNodeName=robot_node_path, color=self.robot_color) if Viewer.backend.startswith('panda3d'): # Add markers' display groups @@ -814,10 +755,6 @@ def get_force_scale(joint_idx: int) -> Tuple[float, float, float]: def open_gui(start_if_needed: bool = False) -> bool: """Open a new viewer graphical interface. - .. note:: - This method does nothing when using Gepetto-gui backend because - its lifetime is tied to the graphical interface. - .. note:: Only one graphical interface can be opened locally for efficiency. """ @@ -829,7 +766,7 @@ def open_gui(start_if_needed: bool = False) -> bool: if Viewer.has_gui(): return - if Viewer.backend in ['gepetto-gui', 'panda3d-qt']: + if Viewer.backend == 'panda3d-qt': # No instance is considered manager of the unique window pass elif Viewer.backend == 'panda3d': @@ -936,10 +873,6 @@ def has_gui() -> bool: def wait(require_client: bool = False) -> None: """Wait for all the meshes to finish loading in every clients. - .. note:: - It is a non-op for `gepetto-gui` since it works in synchronous - mode. - :param require_client: Wait for at least one client to be available before checking for mesh loading. """ @@ -1047,106 +980,13 @@ def close(self=None) -> None: # At this point, consider the viewer has been closed, no matter what self.__is_open = False - @staticmethod - def _get_colorized_urdf(robot: jiminy.Model, - rgb: Tuple3FType, - output_root_path: Optional[str] = None) -> str: - """Generate a unique colorized URDF for a given robot model. - - .. note:: - Multiple identical URDF model of different colors can be loaded in - Gepetto-viewer this way. - - :param robot: jiminy.Model already initialized for the desired URDF. - :param rgb: RGB code defining the color of the model. It is the same - for each link. - :param output_root_path: Root directory of the colorized URDF data. - Optional: temporary directory by default. - - :returns: Full path of the colorized URDF file. - """ - # Get the URDF path and mesh directory search paths if any - urdf_path = robot.urdf_path - mesh_package_dirs = robot.mesh_package_dirs - - # Make sure the robot is associated with an existing URDF - if not urdf_path: - raise RuntimeError( - "Impossible to call this method if the robot is not " - "associated with any URDF.") - - # Define color tag and string representation - color_tag = " ".join(map(str, list(rgb) + [1.0])) - color_str = "_".join(map(str, list(rgb) + [1.0])) - - # Create the output directory - if output_root_path is None: - output_root_path = tempfile.mkdtemp() - colorized_data_dir = os.path.join( - output_root_path, f"colorized_urdf_rgb_{color_str}") - os.makedirs(colorized_data_dir, exist_ok=True) - colorized_urdf_path = os.path.join( - colorized_data_dir, os.path.basename(urdf_path)) - - # Parse the URDF file - tree = ET.parse(robot.urdf_path) - root = tree.getroot() - - # Update mesh fullpath and material color for every visual - for visual in root.iterfind('./link/visual'): - # Get mesh full path - for geom in visual.iterfind('geometry'): - # Get mesh path if any, otherwise skip the geometry - mesh_descr = geom.find('mesh') - if mesh_descr is None: - continue - mesh_fullpath = mesh_descr.get('filename') - - # Make sure mesh path is fully qualified and exists - mesh_realpath = None - if mesh_fullpath.startswith('package://'): - for mesh_dir in mesh_package_dirs: - mesh_searchpath = os.path.join( - mesh_dir, mesh_fullpath[10:]) - if os.path.exists(mesh_searchpath): - mesh_realpath = mesh_searchpath - break - else: - mesh_realpath = mesh_fullpath - assert mesh_realpath is not None, ( - f"Invalid mesh path '{mesh_fullpath}'.") - - # Copy original meshes to temporary directory - colorized_mesh_fullpath = os.path.join( - colorized_data_dir, mesh_realpath[1:]) - colorized_mesh_path = os.path.dirname(colorized_mesh_fullpath) - if not os.access(colorized_mesh_path, os.F_OK): - os.makedirs(colorized_mesh_path) - shutil.copy2(mesh_realpath, colorized_mesh_fullpath) - - # Update mesh fullpath - geom.find('mesh').set('filename', mesh_realpath) - - # Override color tag, remove existing one, if any - material = visual.find('material') - if material is not None: - visual.remove(material) - material = ET.SubElement(visual, 'material', name='') - ET.SubElement(material, 'color', rgba=color_tag) - - # Write on disk the generated URDF file - tree = ET.ElementTree(root) - tree.write(colorized_urdf_path) - - return colorized_urdf_path - @staticmethod @__with_lock def __connect_backend(start_if_needed: bool = False, open_gui: Optional[bool] = None, close_at_exit: bool = True, timeout: int = 2000) -> None: - """Get a pointer to the running process of Gepetto-Viewer. + """Get the running process of backend client. This method can be used to open a new process if necessary. @@ -1159,63 +999,9 @@ def __connect_backend(start_if_needed: bool = False, :param close_at_exit: Terminate backend server at Python exit. Optional: True by default - :returns: Pointer to the running Gepetto-viewer Client and its PID. + :returns: Pointer to the running backend Client and its PID. """ - if Viewer.backend == 'gepetto-gui': - from gepetto.corbaserver.client import Client as gepetto_client - - if open_gui is not None and not open_gui: - logger.warning( - "This option is not available for Gepetto-gui.") - open_gui = False - - def _gepetto_client_connect(get_proc_info=False): - nonlocal close_at_exit - - # Get the existing Gepetto client - client = gepetto_client() - - # Try to fetch the list of scenes to make sure that the Gepetto - # client is responding. - client.gui.getSceneList() - - # Get the associated process information if requested - if not get_proc_info: - return client - proc = [p for p in psutil.process_iter() - if p.cmdline() and 'gepetto-gui' in p.cmdline()[0]][0] - return client, _ProcessWrapper(proc, close_at_exit) - - try: - client, proc = _gepetto_client_connect(get_proc_info=True) - except Viewer._backend_exceptions: - try: - client, proc = _gepetto_client_connect(get_proc_info=True) - except Viewer._backend_exceptions: - if start_if_needed: - FNULL = open(os.devnull, 'w') - proc = subprocess.Popen( - ['gepetto-gui'], shell=False, stdout=FNULL, - stderr=FNULL) - proc = _ProcessWrapper(proc, close_at_exit) - # Must try at least twice for robustness - is_connected = False - for _ in range(max(2, int(timeout / 200))): - time.sleep(0.2) - try: - client = _gepetto_client_connect() - is_connected = True - continue - except Viewer._backend_exceptions: - pass - if not is_connected: - raise RuntimeError( - "Impossible to open Gepetto-viewer.") - else: - raise RuntimeError( - "No backend server to connect to but " - "'start_if_needed' is set to False") - elif Viewer.backend.startswith('panda3d'): + if Viewer.backend.startswith('panda3d'): # handle default argument(s) if open_gui is None: open_gui = True @@ -1331,7 +1117,7 @@ def _gepetto_client_connect(get_proc_info=False): @__must_be_open @__with_lock def _delete_nodes_viewer(nodes_path: Sequence[str]) -> None: - """Delete a 'node' in Gepetto-viewer. + """Delete an object or a group of objects in the scene. .. note:: Be careful, one must specify the full path of a node, including all @@ -1340,10 +1126,7 @@ def _delete_nodes_viewer(nodes_path: Sequence[str]) -> None: :param nodes_path: Full path of the node to delete """ - if Viewer.backend == 'gepetto-gui': - for node_path in nodes_path: - Viewer._backend_obj.gui.deleteNode(node_path, True) - elif Viewer.backend.startswith('panda3d'): + if Viewer.backend.startswith('panda3d'): for node_path in nodes_path: try: Viewer._backend_obj.gui.remove_group(node_path) @@ -1363,10 +1146,7 @@ def set_watermark(img_fullpath: Optional[str] = None, .. note:: The relative width and height cannot exceed 20% of the visible - area, othewise it will be rescaled. - - .. note:: - Gepetto-gui is not supported by this method and will never be. + area, otherwise it will be rescaled. :param img_fullpath: Full path of the image to use as watermark. Meshcat supports format '.png', '.jpeg' or 'svg', @@ -1380,10 +1160,7 @@ def set_watermark(img_fullpath: Optional[str] = None, image manually. Optional: None by default. """ - if Viewer.backend == 'gepetto-gui': - logger.warning( - "Adding watermark is not available for Gepetto-gui.") - elif Viewer.backend.startswith('panda3d'): + if Viewer.backend.startswith('panda3d'): Viewer._backend_obj.gui.set_watermark(img_fullpath, width, height) else: width = width or DEFAULT_WATERMARK_MAXSIZE[0] @@ -1401,9 +1178,6 @@ def set_legend(labels: Optional[Sequence[str]] = None) -> None: Make sure to have specified different colors for each robot on the scene, since it will be used as marker on the legend. - .. note:: - Gepetto-gui is not supported by this method and will never be. - :param labels: Sequence of strings whose length must be consistent with the number of robots on the scene. None to disable. Optional: None by default. @@ -1412,9 +1186,7 @@ def set_legend(labels: Optional[Sequence[str]] = None) -> None: if labels is not None: assert len(labels) == len(Viewer._backend_robot_colors) - if Viewer.backend == 'gepetto-gui': - logger.warning("Adding legend is not available for Gepetto-gui.") - elif Viewer.backend.startswith('panda3d'): + if Viewer.backend.startswith('panda3d'): if labels is None: items = None else: @@ -1464,11 +1236,7 @@ def get_camera_transform(self) -> Tuple[Tuple3FType, Tuple3FType]: this method is valid as long as the user does not move the camera manually using mouse camera control. """ - if Viewer.backend == 'gepetto-gui': - xyzquat = self._gui.getCameraTransform(self._client.windowID) - xyzrpy = XYZQuatToXYZRPY(xyzquat) - xyz, rpy = xyzrpy[:3], xyzrpy[3:] - elif Viewer.backend.startswith('panda3d'): + if Viewer.backend.startswith('panda3d'): xyz, quat = self._gui.get_camera_transform() rot = pin.Quaternion(*quat).matrix() rpy = matrixToRpy(rot @ CAMERA_INV_TRANSFORM_PANDA3D.T) @@ -1543,11 +1311,7 @@ def set_camera_transform(self, return self.set_camera_transform(position, rotation) # Perform the desired transformation - if Viewer.backend == 'gepetto-gui': - H_abs = SE3(rotation_mat, position) - self._gui.setCameraTransform( - self._client.windowID, SE3ToXYZQUAT(H_abs).tolist()) - elif Viewer.backend.startswith('panda3d'): + if Viewer.backend.startswith('panda3d'): rotation_panda3d = pin.Quaternion( rotation_mat @ CAMERA_INV_TRANSFORM_PANDA3D).coeffs() self._gui.set_camera_transform(position, rotation_panda3d) @@ -1804,34 +1568,15 @@ def capture_frame(self, raw_data: bool = False) -> Union[np.ndarray, bytes]: """Take a snapshot and return associated data. - :param width: Width for the image in pixels (not available with - Gepetto-gui for now). None to keep unchanged. + :param width: Width for the image in pixels. None to keep unchanged. Optional: Kept unchanged by default. - :param height: Height for the image in pixels (not available with - Gepetto-gui for now). None to keep unchanged. + :param height: Height for the image in pixels. None to keep unchanged. Optional: Kept unchanged by default. :param raw_data: Whether to return a 2D numpy array, or the raw output from the backend (the actual type may vary). """ # Check user arguments - if Viewer.backend == 'gepetto-gui' and ( - width is not None or height is not None): - logger.warning( - "Specifying window size is not available for Gepetto-gui.") - - if raw_data: - raise NotImplementedError( - "Raw data mode is not available for Gepetto-gui.") - - if Viewer.backend == 'gepetto-gui': - # It is not possible to capture frame directly using gepetto-gui, - # and it is not able to save the frame if the file does not have - # ".png" extension. - with tempfile.NamedTemporaryFile(suffix=".png") as f: - self.save_frame(f.name) - img_obj = Image.open(f.name) - rgba_array = np.array(img_obj) - elif Viewer.backend.startswith('panda3d'): + if Viewer.backend.startswith('panda3d'): # Resize window if size has changed _width, _height = self._gui.getSize() if width is None: @@ -1878,17 +1623,13 @@ def save_frame(self, """Save a snapshot in png format. :param image_path: Fullpath of the image (.png extension is mandatory) - :param width: Width for the image in pixels (not available with - Gepetto-gui for now). None to keep unchanged. + :param width: Width for the image in pixels. None to keep unchanged. Optional: Kept unchanged by default. - :param height: Height for the image in pixels (not available with - Gepetto-gui for now). None to keep unchanged. + :param height: Height for the image in pixels. None to keep unchanged. Optional: Kept unchanged by default. """ image_path = str(pathlib.Path(image_path).with_suffix('.png')) - if Viewer.backend == 'gepetto-gui': - self._gui.captureFrame(self._client.windowID, image_path) - elif Viewer.backend.startswith('panda3d'): + if Viewer.backend.startswith('panda3d'): _width, _height = self._gui.getSize() if width is None: width = _width @@ -2246,15 +1987,7 @@ def refresh(self, self._client.model, self._client.data, model, data) # Render new geometries placements - if Viewer.backend == 'gepetto-gui': - for geom_model, geom_data, model_type in zip( - model_list, data_list, model_type_list): - self._gui.applyConfigurations( - [self._client.getViewerNodeName(geom, model_type) - for geom in geom_model.geometryObjects], - [SE3ToXYZQUATtuple(geom_data.oMg[i]) - for i in range(len(geom_model.geometryObjects))]) - elif Viewer.backend.startswith('panda3d'): + if Viewer.backend.startswith('panda3d'): for geom_model, geom_data, model_type in zip( model_list, data_list, model_type_list): pose_dict = {} @@ -2313,10 +2046,6 @@ def refresh(self, self._gui.set_materials(self._markers_group, material_dict) self._gui.set_scales(self._markers_group, scale_dict) - # Refreshing viewer backend manually if necessary - if Viewer.backend == 'gepetto-gui': - self._gui.refresh() - # Wait for the backend viewer to finish rendering if requested if wait: Viewer.wait(require_client=False)