Visualize

class BaseVisualizer(model=Nb joints = 1 (nq=0, nv=0)   Joint 0 universe: parent=0, collision_model=None, visual_model=None, copy_models=False, data=None, collision_data=None, visual_data=None)[source]

Pinocchio visualizers are employed to easily display a model at a given configuration. BaseVisualizer is not meant to be directly employed, but only to provide a uniform interface and a few common methods. New visualizers should extend this class and override its methods as neeeded.

captureImage(w=None, h=None)[source]

Captures an image from the viewer and returns an RGB array.

clean()[source]

Delete all the objects from the whole scene

create_video_ctx(filename: str = None, fps=30, directory=None, **kwargs)[source]

Create a video recording context, generating the output filename if necessary.

Code inspired from https://github.com/petrikvladimir/RoboMeshCat.

display(q=None)[source]

Display the robot at configuration q or refresh the rendering from the current placements contained in data by placing all the bodies in the viewer.

displayCollisions(visibility)[source]

Set whether to display collision objects or not.

displayVisuals(visibility)[source]

Set whether to display visual objects or not.

drawFrameVelocities(*args)[source]

Draw current frame velocities.

getViewerNodeName(geometry_object, geometry_type)[source]

Return the name of the geometry object inside the viewer.

initViewer(*args, **kwargs)[source]

Init the viewer by loading the gui and creating a window.

loadViewerModel(*args, **kwargs)[source]

Create the scene displaying the robot meshes in the viewer

play(qs, dt=None, callback=None, **kwargs)[source]

Play a trajectory with given time step. Optionally capture RGB images and returns them.

rebuildData()[source]

Re-build the data objects. Needed if the models were modified. Warning: this will delete any information stored in all data objects.

reload(new_geometry_object, geometry_type=None)[source]

Reload a geometry_object given by its type

setBackgroundColor()[source]

Set the visualizer background color.

setCameraPose(pose: ndarray = array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]))[source]

Set camera 6D pose using a 4x4 matrix.

setCameraPosition(position: ndarray)[source]

Set the camera’s 3D position.

setCameraTarget(target)[source]

Set the camera target.

setCameraZoom(zoom: float)[source]

Set camera zoom value.

class GepettoVisualizer(model=Nb joints = 1 (nq=0, nv=0)   Joint 0 universe: parent=0, collision_model=None, visual_model=None, copy_models=False, data=None, collision_data=None, visual_data=None)[source]

A Pinocchio display using Gepetto Viewer

display(q=None)[source]

Display the robot at configuration q in the viewer by placing all the bodies.

displayCollisions(visibility)[source]

Set whether to display collision objects or not

displayVisuals(visibility)[source]

Set whether to display visual objects or not

getViewerNodeName(geometry_object, geometry_type)[source]

Return the name of the geometry object inside the viewer

initViewer(viewer=None, windowName='python-pinocchio', sceneName='world', loadModel=False)[source]

Init GepettoViewer by loading the gui and creating a window.

loadViewerGeometryObject(geometry_object, geometry_type)[source]

Load a single geometry object

loadViewerModel(rootNodeName='pinocchio')[source]

Create the scene displaying the robot meshes in gepetto-viewer

class MeshcatVisualizer(*args, **kwargs)[source]

A Pinocchio display using Meshcat

addGeometryObject(obj: GeometryObject, color=None)[source]

Add a visual GeometryObject to the viewer, with an optional color.

captureImage(w=None, h=None)[source]

Capture an image from the Meshcat viewer and return an RGB array.

clean()[source]

Delete all the objects from the whole scene

display(q=None)[source]

Display the robot at configuration q in the viewer by placing all the bodies.

displayCollisions(visibility)[source]

Set whether to display collision objects or not.

displayVisuals(visibility)[source]

Set whether to display visual objects or not.

drawFrameVelocities(frame_id: int, v_scale=0.2, color=65280)[source]

Draw current frame velocities.

getViewerNodeName(geometry_object, geometry_type)[source]

Return the name of the geometry object inside the viewer.

initViewer(viewer=None, open=False, loadModel=False, zmq_url=None)[source]

Start a new MeshCat server and client. Note: the server can also be started separately using the “meshcat-server” command in a terminal: this enables the server to remain active after the current script ends.

loadViewerGeometryObject(geometry_object, geometry_type, color=None)[source]

Load a single geometry object

loadViewerModel(rootNodeName='pinocchio', color=None)[source]

Load the robot in a MeshCat viewer. :param rootNodeName: name to give to the robot in the viewer :param color: optional, color to give to the robot. This overwrites the color present in the urdf.

Format is a list of four RGBA floats (between 0 and 1)

reload(new_geometry_object, geometry_type=None)[source]

Reload a geometry_object given by its name and its type

setBackgroundColor(preset_name: str = 'gray', col_top=None, col_bot=None)[source]

Set the background.

setCameraPose(pose)[source]

Set camera 6D pose using a 4x4 matrix.

setCameraPosition(position: ndarray)[source]

Set the camera’s 3D position.

setCameraPreset(preset_key: str)[source]

Set the camera angle and position using a given preset.

setCameraTarget(target: ndarray)[source]

Set the camera target.

setCameraZoom(zoom: float)[source]

Set camera zoom value.

class Panda3dVisualizer(model=Nb joints = 1 (nq=0, nv=0)   Joint 0 universe: parent=0, collision_model=None, visual_model=None, copy_models=False, data=None, collision_data=None, visual_data=None)[source]

A Pinocchio display using panda3d engine.

display(q=None)[source]

Display the robot at configuration q in the viewer by placing all the bodies.

displayCollisions(visibility)[source]

Set whether to display collision objects or not.

displayVisuals(visibility)[source]

Set whether to display visual objects or not.

getViewerNodeName(geometry_object, geometry_type)[source]

Return the name of the geometry object inside the viewer.

initViewer(viewer=None, load_model=False)[source]

Init the viewer by attaching to / creating a GUI viewer.

loadViewerModel(group_name, color=None)[source]

Create a group of nodes displaying the robot meshes in the viewer.

class RVizVisualizer(model=Nb joints = 1 (nq=0, nv=0)   Joint 0 universe: parent=0, collision_model=None, visual_model=None, copy_models=False, data=None, collision_data=None, visual_data=None)[source]

A Pinocchio display using RViz

clean()[source]

Delete all the objects from the whole scene

display(q=None)[source]

Display the robot at configuration q in the viz by placing all the bodies.

displayCollisions(visibility)[source]

Set whether to display collision objects or not

displayVisuals(visibility)[source]

Set whether to display visual objects or not

initViewer(viewer=None, windowName='python-pinocchio', loadModel=False, initRosNode=True)[source]

Init RVizViewer by starting a ros node (or not) and creating an RViz window.

loadViewerModel(rootNodeName='pinocchio')[source]

Create the displays in RViz and create publishers for the MarkerArray