Drake
Drake C++ Documentation
Meshcat Class Reference

Detailed Description

Provides an interface to Meshcat (https://github.com/rdeits/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/rdeits/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.

#include <drake/geometry/meshcat.h>

Classes

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 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)
 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)
 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)
 Sets the "object" at path in the scene tree to a triangular mesh with per-vertex coloring. 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, background, grid lines, and axes to their default settings. More...
 
void SetTransform (std::string_view path, const math::RigidTransformd &X_ParentPath)
 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 SetRealtimeRate (double rate)
 Sets the realtime rate that is displayed in the meshcat visualizer stats strip chart. More...
 
void SetProperty (std::string_view path, std::string property, bool value)
 Sets a single named property of the object at the given path. More...
 
void SetProperty (std::string_view path, std::string property, double value)
 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)
 Sets a single named property of the object at the given path. 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...
 
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
 
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)
 Adds a button with the label name to the meshcat browser controls GUI. More...
 
int GetButtonClicks (std::string_view name)
 Returns the number of times the button name has been clicked in the GUI, from the time that it was added to this. More...
 
void DeleteButton (std::string name)
 Removes the button name from the GUI. More...
 
void AddSlider (std::string name, double min, double max, double step, double value)
 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)
 Gets the current value of the slider name. More...
 
void DeleteSlider (std::string name)
 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...
 

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 7099).

Precondition
We require 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)

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

If the button already existed, then resets its click count to zero instead.

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

◆ AddSlider()

void AddSlider ( std::string  name,
double  min,
double  max,
double  step,
double  value 
)

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.

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()

void DeleteButton ( std::string  name)

Removes the button name from the GUI.

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

◆ DeleteSlider()

void DeleteSlider ( std::string  name)

Removes the slider name from the GUI.

Exceptions
std::exceptionif 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.

◆ GetButtonClicks()

int GetButtonClicks ( std::string_view  name)

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.

◆ 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

◆ GetSliderValue()

double GetSliderValue ( std::string_view  name)

Gets the current value of the slider name.

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

◆ HasPath()

bool HasPath ( std::string_view  path) const

◆ operator=() [1/2]

Meshcat& operator= ( Meshcat &&  )
delete

◆ operator=() [2/2]

Meshcat& operator= ( const Meshcat )
delete

◆ port()

int port ( ) const

Returns the port on localhost listening for http connections.

◆ ResetRenderMode()

void ResetRenderMode ( )

Resets the default camera, 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.

◆ 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.

◆ 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.

◆ 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 
)

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 
)

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.

◆ SetProperty() [2/3]

void SetProperty ( std::string_view  path,
std::string  property,
double  value 
)

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.

◆ SetProperty() [3/3]

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

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.

◆ SetRealtimeRate()

void SetRealtimeRate ( double  rate)

Sets the realtime rate that is displayed in the meshcat visualizer stats strip chart.

This rate is the ratio between sim time and real world time. 1 indicates the simulator is the same speed as real time. 2 indicates running twice as fast as real time, 0.5 is half speed, etc.

See also
drake::systems::Simulator::set_target_realtime_rate()
Parameters
ratethe realtime rate value to be displayed, will be converted to a percentage (multiplied by 100)

◆ 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 
)

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.

◆ 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).

◆ 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 
)

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 color values, one color per vertex of the mesh.
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 
)

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.

◆ 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.

◆ 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: