Drake
Drake C++ Documentation
Meshcat Class Reference

Detailed Description

Provides an interface to Meshcat (https://github.com/meshcat-dev/meshcat).

Each instance of this class spawns a thread which runs an http/websocket server. Users can navigate their browser to the hosted URL to visualize the Meshcat scene. Note that, unlike many visualizers, one cannot open the visualizer until this server is running.

Warning
In the current implementation, Meshcat methods must be called from the same thread where the class instance was constructed. For example, running multiple simulations in parallel using the same Meshcat instance is not yet supported. We may generalize this in the future.

Meshcat paths and the scene tree

https://github.com/meshcat-dev/meshcat#api provides a nice introduction to the websocket API that we wrap with this class. One of the core concepts is the "scene tree" – a directory-like structure of objects, transforms, and properties. The scene tree is viewable in the browser by clicking on "Open Controls" in the top right corner.

Elements of the tree are referenced programmatically by a "/"-delimited string indicating the object's path in the scene tree. An object at path "/foo/bar" is a child of an object at path "/foo", so setting the transform of (or deleting) "/foo" will also affect its children.

The string path arguments to the methods in this class use the following semantics:

  • A path that begins with "/" is treated as an absolute path, and is used without modification.
  • A path that does not begin with "/" is treated as a relative path to the default working directory.
  • The "working directory" is fixed to be "/drake" in the current implementation. So any relative path "foo" will be treated as "/drake/foo".
  • Delete("/foo") will remove all objects, transforms, and properties in "/foo" and its children from the scene tree.
  • Delete() is equivalent to Delete("") or Delete("/drake/").
  • SetObject("/foo", ...) places the object at "/foo/<object>", where "<object>" is a hard-coded suffix used for all objects. You can use the Delete("/foo/<object>") to delete the object only (and not the children of "/foo") and must use SetProperty("/foo/<object>", ...) to change object-specific properties.

The root directory contains a number of elements that are set up automatically in the browser. These include "/Background", "/Lights", "/Grid", and "/Cameras". To find more details please see the meshcat documentation and the three.js documentation .

  • You can modify these elements, create new lights/cameras, and even delete these elements (one at a time).
  • Delete("/") is not allowed. It will be silently ignored.

Recommended workflow

For convenience, Meshcat fosters a work flow in which all user-created objects created in Drake are contained in the "/drake" folder. Objects added with a relative path are placed in the "/drake" folder for you. The benefits are:

  • It's simple to distinguish between user objects and "infrastructure" objects in the visualizer.
  • All user objects can easily be cleared by a single, parameter-free call to Delete(). You are welcome to use absolute paths to organize your data, but the burden on tracking and cleaning them up lie on you.

Parameters for the hosted Meshcat page

Meshcat has an experimental AR/VR option (using WebXR). It can be enabled through url parameters. For example, for a meshcat url http://localhost:7000, the following will enable the VR mode:

http://localhost:7000?webxr=vr

To to use augmented reality (where the meshcat background is replaced with your device's camera image), use:

http://localhost:7000?webxr=ar

If augmented reality is not available, it will fallback to VR mode.

Some notes on using the AR/VR modes:

  • Before starting the WebXR session, position the interactive camera to be approximately where you want the origin of the head set's origin to be.
  • The meshcat scene controls are disabled while the WebXR session is active.
  • WebXR sessions can only be run with perspective cameras.
  • The controllers can be visualized but currently can't interact with the Drake simulation physically. To visualize the controllers append the additional url parameter controller=on as in http://localhost:7000?webxr=vr&controller=on.

If you do not have AR/VR hardware, you can use an emulator in your browser to experiment with the mode. Use an browser plugin like WebXR API Emulator (i.e., for Chrome or Firefox).

The AR/VR mode is not currently supported in offline mode (i.e., when saving as StaticHtml()).

Network access

See MeshcatParams for options to control the hostname and port to bind to.

See DRAKE_ALLOW_NETWORK for an environment variable option to deny Meshcat entirely.

#include <drake/geometry/meshcat.h>

Classes

struct  Gamepad
 Status of a gamepad obtained from the Meshcat javascript client. More...
 
struct  OrthographicCamera
 Properties for an orthographic camera in three.js: https://threejs.org/docs/#api/en/cameras/OrthographicCamera. More...
 
struct  PerspectiveCamera
 Properties for a perspective camera in three.js: https://threejs.org/docs/#api/en/cameras/PerspectiveCamera. More...
 

Public Types

enum  SideOfFaceToRender { kFrontSide = 0, kBackSide = 1, kDoubleSide = 2 }
 

Public Member Functions

 Meshcat (std::optional< int > port=std::nullopt)
 Constructs the Meshcat instance on port. More...
 
 Meshcat (const MeshcatParams &params)
 Constructs the Meshcat instance using the given params. More...
 
 ~Meshcat ()
 
std::string web_url () const
 Returns the hosted http URL. More...
 
int port () const
 Returns the port on localhost listening for http connections. More...
 
std::string ws_url () const
 (Advanced) Returns the ws:// URL for direct connection to the websocket interface. More...
 
int GetNumActiveConnections () const
 (Advanced) Returns the number of currently-open websocket connections. More...
 
void Flush () const
 Blocks the calling thread until all buffered data in the websocket thread has been sent to any connected clients. More...
 
void SetObject (std::string_view path, const Shape &shape, const Rgba &rgba=Rgba(.9,.9,.9, 1.))
 Sets the 3D object at a given path in the scene tree. More...
 
void SetObject (std::string_view path, const perception::PointCloud &point_cloud, double point_size=0.001, const Rgba &rgba=Rgba(.9,.9,.9, 1.))
 Sets the "object" at a given path in the scene tree to be point_cloud. More...
 
void SetObject (std::string_view path, const TriangleSurfaceMesh< double > &mesh, const Rgba &rgba=Rgba(0.1, 0.1, 0.1, 1.0), bool wireframe=false, double wireframe_line_width=1.0, SideOfFaceToRender side=kDoubleSide)
 Sets the "object" at path in the scene tree to a TriangleSurfaceMesh. More...
 
void SetLine (std::string_view path, const Eigen::Ref< const Eigen::Matrix3Xd > &vertices, double line_width=1.0, const Rgba &rgba=Rgba(0.1, 0.1, 0.1, 1.0))
 Sets the "object" at path in the scene tree to a piecewise-linear interpolation between the vertices. More...
 
void SetLineSegments (std::string_view path, const Eigen::Ref< const Eigen::Matrix3Xd > &start, const Eigen::Ref< const Eigen::Matrix3Xd > &end, double line_width=1.0, const Rgba &rgba=Rgba(0.1, 0.1, 0.1, 1.0))
 Sets the "object" at path in the scene tree to a number of line segments. More...
 
void SetTriangleMesh (std::string_view path, const Eigen::Ref< const Eigen::Matrix3Xd > &vertices, const Eigen::Ref< const Eigen::Matrix3Xi > &faces, const Rgba &rgba=Rgba(0.1, 0.1, 0.1, 1.0), bool wireframe=false, double wireframe_line_width=1.0, SideOfFaceToRender side=kDoubleSide)
 Sets the "object" at path in the scene tree to a triangular mesh. More...
 
void SetTriangleColorMesh (std::string_view path, const Eigen::Ref< const Eigen::Matrix3Xd > &vertices, const Eigen::Ref< const Eigen::Matrix3Xi > &faces, const Eigen::Ref< const Eigen::Matrix3Xd > &colors, bool wireframe=false, double wireframe_line_width=1.0, SideOfFaceToRender side=kDoubleSide)
 Sets the "object" at path in the scene tree to a triangular mesh with per-vertex coloring. More...
 
void PlotSurface (std::string_view path, const Eigen::Ref< const Eigen::MatrixXd > &X, const Eigen::Ref< const Eigen::MatrixXd > &Y, const Eigen::Ref< const Eigen::MatrixXd > &Z, const Rgba &rgba=Rgba(0.1, 0.1, 0.9, 1.0), bool wireframe=false, double wireframe_line_width=1.0)
 Sets the "object" at path to be a triangle surface mesh representing a 3D surface, via an API that roughly follows matplotlib's plot_surface() method. More...
 
void SetCamera (PerspectiveCamera camera, std::string path="/Cameras/default/rotated")
 Sets the Meshcat object on path to a perspective camera. More...
 
void SetCamera (OrthographicCamera camera, std::string path="/Cameras/default/rotated")
 Sets the Meshcat object on path to an orthographic camera. More...
 
void Set2dRenderMode (const math::RigidTransformd &X_WC=math::RigidTransformd(Eigen::Vector3d{0, -1, 0}), double xmin=-1, double xmax=1, double ymin=-1, double ymax=1)
 Applies a number of settings to make Meshcat act as a 2D renderer. More...
 
void ResetRenderMode ()
 Resets the default camera, camera target, background, grid lines, and axes to their default settings. More...
 
void SetCameraTarget (const Eigen::Vector3d &target_in_world)
 Positions the camera's view target point T to the location in target_in_world (p_WT). More...
 
void SetCameraPose (const Eigen::Vector3d &camera_in_world, const Eigen::Vector3d &target_in_world)
 A convenience function for positioning the camera and its view target in the world frame. More...
 
std::optional< math::RigidTransformd > GetTrackedCameraPose () const
 Returns the most recently received camera pose. More...
 
void SetTransform (std::string_view path, const math::RigidTransformd &X_ParentPath, std::optional< double > time_in_recording=std::nullopt)
 Set the RigidTransform for a given path in the scene tree relative to its parent path. More...
 
void SetTransform (std::string_view path, const Eigen::Ref< const Eigen::Matrix4d > &matrix)
 Set the homogeneous transform for a given path in the scene tree relative to its parent path. More...
 
void Delete (std::string_view path="")
 Deletes the object at the given path as well as all of its children. More...
 
void SetProperty (std::string_view path, std::string property, bool value, std::optional< double > time_in_recording=std::nullopt)
 Sets a single named property of the object at the given path. More...
 
void SetProperty (std::string_view path, std::string property, double value, std::optional< double > time_in_recording=std::nullopt)
 Sets a single named property of the object at the given path. More...
 
void SetProperty (std::string_view path, std::string property, const std::vector< double > &value, std::optional< double > time_in_recording=std::nullopt)
 Sets a single named property of the object at the given path. More...
 
void SetEnvironmentMap (const std::filesystem::path &image_path)
 Sets the environment texture. More...
 
void SetAnimation (const MeshcatAnimation &animation)
 Sets the MeshcatAnimation, which creates a slider interface element to play/pause/rewind through a series of animation frames in the visualizer. More...
 
std::string StaticHtml ()
 Returns an HTML string that can be saved to a file for a snapshot of the visualizer and its contents. More...
 
void StartRecording (double frames_per_second=64.0, bool set_visualizations_while_recording=true)
 Sets a flag indicating that subsequent calls to SetTransform and SetProperty should also be "recorded" into a MeshcatAnimation when their optional time_in_recording argument is supplied. More...
 
void StopRecording ()
 Sets a flag to pause/stop recording. More...
 
void PublishRecording ()
 Sends the recording to Meshcat as an animation. More...
 
void DeleteRecording ()
 Deletes the current animation holding the recorded frames. More...
 
const MeshcatAnimationget_recording () const
 Returns a const reference to this Meshcat's MeshcatAnimation object. More...
 
MeshcatAnimationget_mutable_recording ()
 Returns a mutable reference to this Meshcat's MeshcatAnimation object. More...
 
bool HasPath (std::string_view path) const
 
std::string GetPackedObject (std::string_view path) const
 
std::string GetPackedTransform (std::string_view path) const
 
std::string GetPackedProperty (std::string_view path, std::string property) const
 
Does not allow copy, move, or assignment
 Meshcat (const Meshcat &)=delete
 
Meshcatoperator= (const Meshcat &)=delete
 
 Meshcat (Meshcat &&)=delete
 
Meshcatoperator= (Meshcat &&)=delete
 
void SetSimulationTime (double sim_time)
 @group Realtime Rate Reporting More...
 
double GetSimulationTime () const
 Gets the last time value passed to SetSimulationTime(). More...
 
void SetRealtimeRate (double rate)
 Immediately broadcasts the given realtime rate to all connected clients. More...
 
double GetRealtimeRate () const
 Gets the realtime rate that was last broadcast by this instance (typically, the value displayed in the meshcat visualizer stats chart). More...
 
Meshcat Controls

Meshcat "Controls" are user interface elements in the browser.

These currently include buttons and sliders.

  • Controls appear in the browser under the "Open Controls" dropdown menu, and are appended to the root node of the tree (they do not have a path in the "scene tree"), in the order in which they are added.
  • Controls must have unique names. Adding a control with a name that was already in use will overwrite the existing control. If you add a slider with a name that was previous used for a button, then the button will be replaced by the slider, etc.
  • Users of this Meshcat instance are responsible for polling the GUI to retrieve the user interface events.
  • Controls can be added/deleted/accessed anytime during the lifetime of this Meshcat instance.
void AddButton (std::string name, std::string keycode="")
 Adds a button with the label name to the meshcat browser controls GUI. More...
 
int GetButtonClicks (std::string_view name) const
 Returns the number of times the button name has been clicked in the GUI, from the time that it was added to this. More...
 
bool DeleteButton (std::string name, bool strict=true)
 Removes the button name from the GUI. More...
 
void AddSlider (std::string name, double min, double max, double step, double value, std::string decrement_keycode="", std::string increment_keycode="")
 Adds a slider with the label name to the meshcat browser controls GUI. More...
 
void SetSliderValue (std::string name, double value)
 Sets the current value of the slider name. More...
 
double GetSliderValue (std::string_view name) const
 Gets the current value of the slider name. More...
 
std::vector< std::string > GetSliderNames () const
 Returns the names of all sliders. More...
 
bool DeleteSlider (std::string name, bool strict=true)
 Removes the slider name from the GUI. More...
 
void DeleteAddedControls ()
 Removes all buttons and sliders from the GUI that have been registered by this Meshcat instance. More...
 
Gamepad GetGamepad () const
 Returns the status from the most recently updated gamepad data in the Meshcat. More...
 

Member Enumeration Documentation

◆ SideOfFaceToRender

Enumerator
kFrontSide 
kBackSide 
kDoubleSide 

Constructor & Destructor Documentation

◆ Meshcat() [1/4]

Meshcat ( const Meshcat )
delete

◆ Meshcat() [2/4]

Meshcat ( Meshcat &&  )
delete

◆ Meshcat() [3/4]

Meshcat ( std::optional< int port = std::nullopt)
explicit

Constructs the Meshcat instance on port.

If no port is specified, it will listen on the first available port starting at 7000 (up to 7999). If port 0 is specified, it will listen on an arbitrary "ephemeral" port.

Precondition
We require port == 0 || port >= 1024.
Exceptions
std::exceptionif no requested port is available.

◆ Meshcat() [4/4]

Meshcat ( const MeshcatParams params)
explicit

Constructs the Meshcat instance using the given params.

◆ ~Meshcat()

~Meshcat ( )

Member Function Documentation

◆ AddButton()

void AddButton ( std::string  name,
std::string  keycode = "" 
)

Adds a button with the label name to the meshcat browser controls GUI.

If the optional keycode is set to a javascript string key code (such as "KeyG" or "ArrowLeft", see https://developer.mozilla.org/en-US/docs/Web/API/UI_Events/Keyboard_event_code_values), then a keydown callback is registered in the GUI which will also click the button. If the button already existed, then resets its click count to zero; and sets the keycode if no keycode was set before.

Exceptions
std::exceptionif name has already been added as any other type of control (e.g., slider).
std::exceptionif a button of the same name has already been assigned a different keycode.

◆ AddSlider()

void AddSlider ( std::string  name,
double  min,
double  max,
double  step,
double  value,
std::string  decrement_keycode = "",
std::string  increment_keycode = "" 
)

Adds a slider with the label name to the meshcat browser controls GUI.

The slider range is given by [min, max]. step is the smallest increment by which the slider can change values (and therefore send updates back to this Meshcat instance). value specifies the initial value; it will be truncated to the slider range and rounded to the nearest increment. If the optional decrement_keycode or increment_keycode are set to a javascript string key code (such as "KeyG" or "ArrowLeft", see https://developer.mozilla.org/en-US/docs/Web/API/UI_Events/Keyboard_event_code_values), then keydown callbacks will be registered in the GUI that will move the slider by step (within the limits) when those buttons are pressed.

Exceptions
std::exceptionif name has already been added as any type of control (e.g., either button or slider).

◆ Delete()

void Delete ( std::string_view  path = "")

Deletes the object at the given path as well as all of its children.

See Meshcat paths and the scene tree for the detailed semantics of deletion.

◆ DeleteAddedControls()

void DeleteAddedControls ( )

Removes all buttons and sliders from the GUI that have been registered by this Meshcat instance.

It does not clear the default GUI elements set in the meshcat browser (e.g. for cameras and lights).

◆ DeleteButton()

bool DeleteButton ( std::string  name,
bool  strict = true 
)

Removes the button name from the GUI.

Returns
true iff the button was removed.
Exceptions
std::exceptionif strict is true and name is not a registered button.

◆ DeleteRecording()

void DeleteRecording ( )

Deletes the current animation holding the recorded frames.

Animation options (autoplay, repetitions, etc) will also be reset, and any pointers obtained from get_mutable_recording() will be rendered invalid. This does not* currently remove the animation from Meshcat.

◆ DeleteSlider()

bool DeleteSlider ( std::string  name,
bool  strict = true 
)

Removes the slider name from the GUI.

Returns
true iff the slider was removed.
Exceptions
std::exceptionif strict is true and name is not a registered slider.

◆ Flush()

void Flush ( ) const

Blocks the calling thread until all buffered data in the websocket thread has been sent to any connected clients.

This can be especially useful when sending many or large mesh files / texture maps, to avoid large "backpressure" and/or simply to make sure that the simulation does not get far ahead of the visualization.

◆ get_mutable_recording()

MeshcatAnimation& get_mutable_recording ( )

Returns a mutable reference to this Meshcat's MeshcatAnimation object.

This can be used to set animation properties (like autoplay, the loop mode, number of repetitions, etc). The return value will only remain valid for the lifetime of this or until DeleteRecording() is called.

◆ get_recording()

const MeshcatAnimation& get_recording ( ) const

Returns a const reference to this Meshcat's MeshcatAnimation object.

This can be used to check animation properties (e.g., autoplay). The return value will only remain valid for the lifetime of this or until DeleteRecording() is called.

◆ GetButtonClicks()

int GetButtonClicks ( std::string_view  name) const

Returns the number of times the button name has been clicked in the GUI, from the time that it was added to this.

If multiple browsers are open, then this number is the cumulative number of clicks in all browsers.

Exceptions
std::exceptionif name is not a registered button.

◆ GetGamepad()

Gamepad GetGamepad ( ) const

Returns the status from the most recently updated gamepad data in the Meshcat.

See Gamepad for details on the returned values.

Note that in javascript, gamepads are not detected until users "opt-in" by pressing a gamepad button or moving the thumbstick in the Meshcat window. If no gamepad information is available in javascript, then no messages are sent and the returned gamepad index will not have a value.

Currently Meshcat only attempts to support one gamepad. If multiple gamepads are detected in the same Meshcat window, then only the status of the first connected gamepad in navigator.GetGamepads() is returned. If multiple Meshcat windows are connected to this Meshcat instance, and gamepads are being used in multiple windows, then the returned status will be the most recently received status message. Therefore using multiple gamepads simultaneously is not recommended.

This feature is provided primarily to support applications where Drake is running on a remote machine (e.g. in the cloud), and the Meshcat javascript in the browser is the only code running on the local machine which has access to the gamepad.

For more details on javascript support for gamepads (or to test that your gamepad is working), see https://beej.us/blog/data/javascript-gamepad/.

◆ GetNumActiveConnections()

int GetNumActiveConnections ( ) const

(Advanced) Returns the number of currently-open websocket connections.

◆ GetPackedObject()

std::string GetPackedObject ( std::string_view  path) const

◆ GetPackedProperty()

std::string GetPackedProperty ( std::string_view  path,
std::string  property 
) const

◆ GetPackedTransform()

std::string GetPackedTransform ( std::string_view  path) const

◆ GetRealtimeRate()

double GetRealtimeRate ( ) const

Gets the realtime rate that was last broadcast by this instance (typically, the value displayed in the meshcat visualizer stats chart).

See SetRealtimeRate().

◆ GetSimulationTime()

double GetSimulationTime ( ) const

Gets the last time value passed to SetSimulationTime().

◆ GetSliderNames()

std::vector<std::string> GetSliderNames ( ) const

Returns the names of all sliders.

◆ GetSliderValue()

double GetSliderValue ( std::string_view  name) const

Gets the current value of the slider name.

Exceptions
std::exceptionif name is not a registered slider.

◆ GetTrackedCameraPose()

std::optional<math::RigidTransformd> GetTrackedCameraPose ( ) const

Returns the most recently received camera pose.

A meshcat browser session can be configured to transmit its camera pose. It is enabled by appending a url parameter. For example, if the url for the meshcat server is:

http://localhost:7000

A particular browser can be configured to transmit its camera pose back to Drake by supplying the following url:

http://localhost:7000/?tracked_camera=on

It is possible to use that URL in multiple browsers simultaneously. A particular view will only transmit its camera position when its camera position actually changes. As such, the returned camera pose will reflect the pose of the camera from that most-recently manipulated browser.

std::nullopt is returned if:

  • No meshcat session has transmitted its camera pose.
  • The meshcat session that last transmitted its pose is no longer connected.
  • The meshcat session transmitting has an orthographic camera.

◆ HasPath()

bool HasPath ( std::string_view  path) const

◆ operator=() [1/2]

Meshcat& operator= ( Meshcat &&  )
delete

◆ operator=() [2/2]

Meshcat& operator= ( const Meshcat )
delete

◆ PlotSurface()

void PlotSurface ( std::string_view  path,
const Eigen::Ref< const Eigen::MatrixXd > &  X,
const Eigen::Ref< const Eigen::MatrixXd > &  Y,
const Eigen::Ref< const Eigen::MatrixXd > &  Z,
const Rgba rgba = Rgba(0.1, 0.1, 0.9, 1.0),
bool  wireframe = false,
double  wireframe_line_width = 1.0 
)

Sets the "object" at path to be a triangle surface mesh representing a 3D surface, via an API that roughly follows matplotlib's plot_surface() method.

Parameters
Xmatrix of x coordinate values defining the vertices of the mesh.
Ymatrix of y coordinate values.
Zmatrix of z coordinate values.
rgbais the mesh face or wireframe color.
wireframeif "true", then only the triangle edges are visualized, not the faces.
wireframe_line_widthis the width in pixels. Due to limitations in WebGL implementations, the line width may be 1 regardless of the set value.

Typically, X and Y are obtained via, e.g.

constexpr int nx = 15, ny = 11;
X = RowVector<double, nx>::LinSpaced(0, 1).replicate<ny, 1>();
Y = Vector<double, ny>::LinSpaced(0, 1).replicate<1, nx>();

in C++ or e.g.

xs = np.linspace(0, 1, 15)
ys = np.linspace(0, 1, 11)
[X, Y] = np.meshgrid(xs, ys)

in Python, and Z is the surface evaluated on each X, Y value.

Precondition
X, Y, and Z must be the same shape.

◆ port()

int port ( ) const

Returns the port on localhost listening for http connections.

◆ PublishRecording()

void PublishRecording ( )

Sends the recording to Meshcat as an animation.

The published animation only includes transforms and properties; the objects that they modify must be sent to the visualizer separately (e.g. by calling Publish()).

◆ ResetRenderMode()

void ResetRenderMode ( )

Resets the default camera, camera target, background, grid lines, and axes to their default settings.

◆ Set2dRenderMode()

void Set2dRenderMode ( const math::RigidTransformd &  X_WC = math::RigidTransformd(Eigen::Vector3d{0, -1, 0}),
double  xmin = -1,
double  xmax = 1,
double  ymin = -1,
double  ymax = 1 
)

Applies a number of settings to make Meshcat act as a 2D renderer.

The camera is set to an orthographic camera with X_WC specifying the pose of the camera in world. The camera looks down the +Cy axis, with +Cz corresponding to positive y in the 2D frame, and -Cx corresponding to positive x in the 2D frame.

Additionally sets the background, grid lines, and axes "visible" properties to false.

◆ SetAnimation()

void SetAnimation ( const MeshcatAnimation animation)

Sets the MeshcatAnimation, which creates a slider interface element to play/pause/rewind through a series of animation frames in the visualizer.

See also StartRecording(), which records supported calls to this into a MeshcatAnimation, and PublishRecording(), which calls SetAnimation() with the recording.

◆ SetCamera() [1/2]

void SetCamera ( PerspectiveCamera  camera,
std::string  path = "/Cameras/default/rotated" 
)

Sets the Meshcat object on path to a perspective camera.

We provide a default value of path corresponding to the default camera object in Meshcat.

◆ SetCamera() [2/2]

void SetCamera ( OrthographicCamera  camera,
std::string  path = "/Cameras/default/rotated" 
)

Sets the Meshcat object on path to an orthographic camera.

We provide a default value of path corresponding to the default camera object in Meshcat.

◆ SetCameraPose()

void SetCameraPose ( const Eigen::Vector3d &  camera_in_world,
const Eigen::Vector3d &  target_in_world 
)

A convenience function for positioning the camera and its view target in the world frame.

The camera is placed at camera_in_world and looks toward target_in_world. The camera is oriented around this view direction so that the camera's up vector points in the positive Wz direction as much as possible.

Unlike SetCameraTarget() this can be used to orient orthographic cameras as well.

Note
This is Drake's z-up world frame and not the three.js world frame you'd have to use if you set the "position" on the camera directly.
Warning
The behavior is undefined if camera and target positions are coincident.
Parameters
camera_in_worldthe position of the camera's origin C in Drake's z-up world frame (p_WC).
target_in_worldthe position of the target point T in Drake's z-up world frame (p_WT).

◆ SetCameraTarget()

void SetCameraTarget ( const Eigen::Vector3d &  target_in_world)

Positions the camera's view target point T to the location in target_in_world (p_WT).

If the camera is orthographic (i.e., by calling Set2DRenderMode() or SetCamera(OrthographicCamera)), this will have no effect.

Warning
Setting the target position to be coincident with the camera position will lead to undefined behavior.
Parameters
target_in_worldthe position of the target point T in Drake's z-up world frame (p_WT).

◆ SetEnvironmentMap()

void SetEnvironmentMap ( const std::filesystem::path &  image_path)

Sets the environment texture.

For objects with physically-based rendering (PBR) material properties (e.g., metallic surfaces), this defines the luminance environment, contributing to total illumination and appearing in reflections.

The image should be of a format typically supported by web browsers: e.g., jpg, png, etc. Furthermore, the image must be an equirectangular image (as opposed to a cube-map).

If the path is empty, the environment map will be cleared.

Exceptions
ifimage_path is not empty and the file isn't accessible.
Precondition
If image_path names an accessible file, it is an appropriate image type.

◆ SetLine()

void SetLine ( std::string_view  path,
const Eigen::Ref< const Eigen::Matrix3Xd > &  vertices,
double  line_width = 1.0,
const Rgba rgba = Rgba(0.1, 0.1, 0.1, 1.0) 
)

Sets the "object" at path in the scene tree to a piecewise-linear interpolation between the vertices.

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics.
verticesare the 3D points defining the lines.
line_widthis the width in pixels. Due to limitations in WebGL implementations, the line width may be 1 regardless of the set value.
rgbais the line color.

◆ SetLineSegments()

void SetLineSegments ( std::string_view  path,
const Eigen::Ref< const Eigen::Matrix3Xd > &  start,
const Eigen::Ref< const Eigen::Matrix3Xd > &  end,
double  line_width = 1.0,
const Rgba rgba = Rgba(0.1, 0.1, 0.1, 1.0) 
)

Sets the "object" at path in the scene tree to a number of line segments.

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics.
startis a 3-by-N matrix of 3D points defining the start of each segment.
endis a 3-by-N matrix of 3D points defining the end of each segment.
line_widthis the width in pixels. Due to limitations in WebGL implementations, the line width may be 1 regardless of the set value.
rgbais the line color.
Exceptions
std::exceptionif start.cols != end.cols().

◆ SetObject() [1/3]

void SetObject ( std::string_view  path,
const Shape shape,
const Rgba rgba = Rgba(.9,.9,.9, 1.) 
)

Sets the 3D object at a given path in the scene tree.

Note that path="/foo" will always set an object in the tree at "/foo/<object>". See Meshcat paths and the scene tree. Any objects previously set at this path will be replaced.

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics.
shapea Shape that specifies the geometry of the object.
rgbaan Rgba that specifies the (solid) color of the object.
Note
If shape is a mesh, the file referred to can be either an .obj file or an embedded .gltf file (it has all geometry data and texture data contained within the single .gltf file).

◆ SetObject() [2/3]

void SetObject ( std::string_view  path,
const perception::PointCloud point_cloud,
double  point_size = 0.001,
const Rgba rgba = Rgba(.9,.9,.9, 1.) 
)

Sets the "object" at a given path in the scene tree to be point_cloud.

Note that path="/foo" will always set an object in the tree at "/foo/<object>". See Meshcat paths and the scene tree. Any objects previously set at this path will be replaced.

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics.
point_clouda perception::PointCloud; if point_cloud.has_rgbs() is true, then meshcat will render the colored points.
point_sizeis the size of each rendered point.
rgbais the default color, which is only used if point_cloud.has_rgbs() == false.

◆ SetObject() [3/3]

void SetObject ( std::string_view  path,
const TriangleSurfaceMesh< double > &  mesh,
const Rgba rgba = Rgba(0.1, 0.1, 0.1, 1.0),
bool  wireframe = false,
double  wireframe_line_width = 1.0,
SideOfFaceToRender  side = kDoubleSide 
)

Sets the "object" at path in the scene tree to a TriangleSurfaceMesh.

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics.
meshis a TriangleSurfaceMesh object.
rgbais the mesh face or wireframe color.
wireframeif "true", then only the triangle edges are visualized, not the faces.
wireframe_line_widthis the width in pixels. Due to limitations in WebGL implementations, the line width may be 1 regardless of the set value.

◆ SetProperty() [1/3]

void SetProperty ( std::string_view  path,
std::string  property,
bool  value,
std::optional< double time_in_recording = std::nullopt 
)

Sets a single named property of the object at the given path.

For example,

meshcat.SetProperty("/Background", "visible", false);

will turn off the background. See Meshcat paths for more details about these properties and how to address them.

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths and the scene tree for the semantics.
propertythe string name of the property to set
valuethe new value.
time_in_recording(optional). If recording (see StartRecording()), then in addition to publishing the property to any meshcat browsers immediately, this transform is saved to the current animation at time_in_recording.

◆ SetProperty() [2/3]

void SetProperty ( std::string_view  path,
std::string  property,
double  value,
std::optional< double time_in_recording = std::nullopt 
)

Sets a single named property of the object at the given path.

For example,

meshcat.SetProperty("/Lights/DirectionalLight/<object>", "intensity", 1.0);

See Meshcat paths for more details about these properties and how to address them.

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths and the scene tree for the semantics.
propertythe string name of the property to set
valuethe new value.
time_in_recording(optional) the time at which this property should be applied, if Meshcat is current recording (see StartRecording()). If Meshcat is not currently recording, then this value is simply ignored.

◆ SetProperty() [3/3]

void SetProperty ( std::string_view  path,
std::string  property,
const std::vector< double > &  value,
std::optional< double time_in_recording = std::nullopt 
)

Sets a single named property of the object at the given path.

For example,

meshcat.SetProperty("/Background", "top_color", {1.0, 0.0, 0.0});

See Meshcat paths for more details about these properties and how to address them.

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths and the scene tree for the semantics.
propertythe string name of the property to set
valuethe new value.
time_in_recording(optional) the time at which this property should be applied, if Meshcat is current recording (see StartRecording()). If Meshcat is not currently recording, then this value is simply ignored.

◆ SetRealtimeRate()

void SetRealtimeRate ( double  rate)

Immediately broadcasts the given realtime rate to all connected clients.

Parameters
ratethe realtime rate value to broadcast, will be converted to a percentage (multiplied by 100)

◆ SetSimulationTime()

void SetSimulationTime ( double  sim_time)

@group Realtime Rate Reporting

Meshcat can be used to visualize the realtime rate of a simulation's computation in the meshcat visualizer webpage. Meshcat broadcasts a realtime rate message that is received and displayed by the browser in a stats strip chart

Advancing the simulation's time requires a certain amount of real world compute time. The realtime rate, a non-negative real value, is the ratio of the sim time to real world time. A value of one indicates that the simulation is advancing at the same rate as the real world clock. Higher values indicate faster simulations. Lower values indicate slower simulations.

The realtime rate value can be broadcast to the visualizer in one of two ways:

  • Throttled - Meshcat is configured to broadcast realtime rate data in a "smoothed" manner, so that the visualization doesn't fluctuate at arbitrarily high rates and possibly make the value difficult to read. See SetSimulationTime(). This is the preferred means of reporting real time rate.
  • Immediate - a Meshcat user can compute realtime rate themselves and simply ask Meshcat to dispatch a message with that computed value. See SetRealtimeRate(). This is not recommended and the user is responsible for computing the value and controlling the frequency at which this is done.Updates Meshcat's knowledge of simulation time. Changes to simulation time may trigger a realtime rate message to the meshcat visualizer client based on the configured value in MeshcatParams::realtime_rate_period value.

Invoking this method may dispatch a message to clients. The following rules apply to invocations and messages:

  • The first invocation is necessary to initialize the calculation; it defines the the starting point from which all calculations are performed (for both wall clock time as well as simulation time). As no interval can be measured from a single invocation, no rate can be computed. Therefore, the first invocation will never broadcast the message.
  • Wall clock time must advance at least MeshcatParams::realtime_rate_period seconds for a message to be sent.
  • Meshcat promises to broadcast one message per elapsed period – starting from initialization – regardless of the frequency at which SetSimulationTime() actually gets invoked. If the elapsed time between invocations exceeds MeshcatParams::realtime_rate_period, multiple messages will be broadcast; one for each complete period.
    • This implies that each column of pixels in the realtime rate chart in the client visualizer represents a fixed amount of wall clock time.

When the realtime rate is broadcast, that value will be reported by GetRealtimeRate().

The realtime rate calculation can be "reset" by passing a simulation time value that is strictly less than the value of the previous invocation. This has the effect of re-initializing the calculation with the passed time and the wall clock time of the invocation. So, if the simulation's context gets reset to time = 0, calls to this method passing the context time will implicitly reset realtime rate calculations accordingly. Resetting the calculator will reset the value reported by GetRealtimeRate() to zero.

This function is safe to be called redundantly with the same simulation time. Redundant calls are a no-op.

Parameters
sim_timeThe absolute sim time being visualized.
See also
drake::systems::Simulator::set_target_realtime_rate()

◆ SetSliderValue()

void SetSliderValue ( std::string  name,
double  value 
)

Sets the current value of the slider name.

value will be truncated to the slider range and rounded to the nearest increment specified by the slider step. This will update the slider element in all connected meshcat browsers.

Exceptions
std::exceptionif name is not a registered slider.

◆ SetTransform() [1/2]

void SetTransform ( std::string_view  path,
const math::RigidTransformd &  X_ParentPath,
std::optional< double time_in_recording = std::nullopt 
)

Set the RigidTransform for a given path in the scene tree relative to its parent path.

An object's pose is the concatenation of all of the transforms along its path, so setting the transform of "/foo" will move the objects at "/foo/box1" and "/foo/robots/HAL9000".

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics.
X_ParentPaththe relative transform from the path to its immediate parent.
time_in_recording(optional). If recording (see StartRecording()), then in addition to publishing the transform to any meshcat browsers immediately, this transform is saved to the current animation at time_in_recording.

◆ SetTransform() [2/2]

void SetTransform ( std::string_view  path,
const Eigen::Ref< const Eigen::Matrix4d > &  matrix 
)

Set the homogeneous transform for a given path in the scene tree relative to its parent path.

An object's pose is the concatenation of all of the transforms along its path, so setting the transform of "/foo" will move the objects at "/foo/box1" and "/foo/robots/HAL9000".

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics.
matrixthe relative transform from the path to its immediate parent.

Note: Prefer to use the overload which takes a RigidTransformd unless you need the fully parameterized homogeneous transform (which additionally allows scale and sheer).

Note: Meshcat does not properly support non-uniform scaling. See Drake issue #18095.

◆ SetTriangleColorMesh()

void SetTriangleColorMesh ( std::string_view  path,
const Eigen::Ref< const Eigen::Matrix3Xd > &  vertices,
const Eigen::Ref< const Eigen::Matrix3Xi > &  faces,
const Eigen::Ref< const Eigen::Matrix3Xd > &  colors,
bool  wireframe = false,
double  wireframe_line_width = 1.0,
SideOfFaceToRender  side = kDoubleSide 
)

Sets the "object" at path in the scene tree to a triangular mesh with per-vertex coloring.

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics.
verticesis a 3-by-N matrix of 3D point defining the vertices of the mesh.
facesis a 3-by-M integer matrix with each entry denoting an index into vertices and each column denoting one face (aka SurfaceTriangle).
colorsis a 3-by-N matrix of RGB color values, one color per vertex of the mesh. Color values are in the range [0, 1].
wireframeif "true", then only the triangle edges are visualized, not the faces.
wireframe_line_widthis the width in pixels. Due to limitations in WebGL implementations, the line width may be 1 regardless of the set value.

◆ SetTriangleMesh()

void SetTriangleMesh ( std::string_view  path,
const Eigen::Ref< const Eigen::Matrix3Xd > &  vertices,
const Eigen::Ref< const Eigen::Matrix3Xi > &  faces,
const Rgba rgba = Rgba(0.1, 0.1, 0.1, 1.0),
bool  wireframe = false,
double  wireframe_line_width = 1.0,
SideOfFaceToRender  side = kDoubleSide 
)

Sets the "object" at path in the scene tree to a triangular mesh.

Parameters
patha "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics.
verticesis a 3-by-N matrix of 3D point defining the vertices of the mesh.
facesis a 3-by-M integer matrix with each entry denoting an index into vertices and each column denoting one face (aka SurfaceTriangle).
rgbais the mesh face or wireframe color.
wireframeif "true", then only the triangle edges are visualized, not the faces.
wireframe_line_widthis the width in pixels. Due to limitations in WebGL implementations, the line width may be 1 regardless of the set value.

◆ StartRecording()

void StartRecording ( double  frames_per_second = 64.0,
bool  set_visualizations_while_recording = true 
)

Sets a flag indicating that subsequent calls to SetTransform and SetProperty should also be "recorded" into a MeshcatAnimation when their optional time_in_recording argument is supplied.

The data in these events will be combined with any frames previously added to the animation; if the same transform/property is set at the same time, then it will overwrite the existing frame in the animation.

Parameters
set_visualizations_while_recordingif true, then each method will send the visualization immediately to Meshcat and record the visualization in the animation. Set to false to avoid updating the visualization during recording. One exception is calls to SetObject, which will always be sent to the visualizer immediately (because meshcat animations do not support SetObject).

◆ StaticHtml()

std::string StaticHtml ( )

Returns an HTML string that can be saved to a file for a snapshot of the visualizer and its contents.

The HTML can be viewed in the browser without any connection to a Meshcat "server" (e.g. this). This is a great way to save and share your 3D content.

Note that controls (e.g. sliders and buttons) are not included in the HTML output, because their usefulness relies on a connection to the server.

You can also use your browser to download this file, by typing "/download" on the end of the URL (i.e., accessing web_url() + "/download").

◆ StopRecording()

void StopRecording ( )

Sets a flag to pause/stop recording.

When stopped, publish events will not add frames to the animation.

◆ web_url()

std::string web_url ( ) const

Returns the hosted http URL.

◆ ws_url()

std::string ws_url ( ) const

(Advanced) Returns the ws:// URL for direct connection to the websocket interface.

Most users should connect via a browser opened to web_url().


The documentation for this class was generated from the following file: