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.
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:
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 .
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:
#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 ¶ms) | |
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 | |
Meshcat & | operator= (const Meshcat &)=delete |
Meshcat (Meshcat &&)=delete | |
Meshcat & | operator= (Meshcat &&)=delete |
Meshcat Controls | |
Meshcat "Controls" are user interface elements in the browser. These currently include buttons and sliders.
| |
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... | |
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).
port
>= 1024. std::exception | if no requested port is available. |
|
explicit |
Constructs the Meshcat instance using the given params
.
~Meshcat | ( | ) |
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.
std::exception | if name has already been added as any other type of control (e.g., slider). |
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.
std::exception | if name has already been added as any type of control (e.g., either button or slider). |
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.
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).
void DeleteButton | ( | std::string | name | ) |
Removes the button name
from the GUI.
std::exception | if name is not a registered button. |
void DeleteSlider | ( | std::string | name | ) |
Removes the slider name
from the GUI.
std::exception | if name is not a registered slider. |
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.
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.
std::exception | if name is not a registered button. |
int GetNumActiveConnections | ( | ) | const |
(Advanced) Returns the number of currently-open websocket connections.
std::string GetPackedObject | ( | std::string_view | path | ) | const |
std::string GetPackedProperty | ( | std::string_view | path, |
std::string | property | ||
) | const |
std::string GetPackedTransform | ( | std::string_view | path | ) | const |
double GetSliderValue | ( | std::string_view | name | ) |
Gets the current value
of the slider name
.
std::exception | if name is not a registered slider. |
bool HasPath | ( | std::string_view | path | ) | const |
int port | ( | ) | const |
Returns the port on localhost listening for http connections.
void ResetRenderMode | ( | ) |
Resets the default camera, background, grid lines, and axes to their default settings.
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.
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.
void SetCamera | ( | PerspectiveCamera | camera, |
std::string | path = "/Cameras/default/rotated" |
||
) |
void SetCamera | ( | OrthographicCamera | camera, |
std::string | path = "/Cameras/default/rotated" |
||
) |
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
.
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics. |
vertices | are the 3D points defining the lines. |
line_width | is the width in pixels. Due to limitations in WebGL implementations, the line width may be 1 regardless of the set value. |
rgba | is the line color. |
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.
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics. |
start | is a 3-by-N matrix of 3D points defining the start of each segment. |
end | is a 3-by-N matrix of 3D points defining the end of each segment. |
line_width | is the width in pixels. Due to limitations in WebGL implementations, the line width may be 1 regardless of the set value. |
rgba | is the line color. |
std::exception | if start.cols != end.cols(). |
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.
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics. |
shape | a Shape that specifies the geometry of the object. |
rgba | an Rgba that specifies the (solid) color of the object. |
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.
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics. |
point_cloud | a perception::PointCloud; if point_cloud.has_rgbs() is true, then meshcat will render the colored points. |
point_size | is the size of each rendered point. |
rgba | is the default color, which is only used if point_cloud.has_rgbs() == false . |
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.
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics. |
mesh | is a TriangleSurfaceMesh object. |
rgba | is the mesh face or wireframe color. |
wireframe | if "true", then only the triangle edges are visualized, not the faces. |
wireframe_line_width | is the width in pixels. Due to limitations in WebGL implementations, the line width may be 1 regardless of the set value. |
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.
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths and the scene tree for the semantics. |
property | the string name of the property to set |
value | the new value. |
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.
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths and the scene tree for the semantics. |
property | the string name of the property to set |
value | the new value. |
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.
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths and the scene tree for the semantics. |
property | the string name of the property to set |
value | the new value. |
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.
rate | the realtime rate value to be displayed, will be converted to a percentage (multiplied by 100) |
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.
std::exception | if name is not a registered slider. |
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".
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics. |
X_ParentPath | the relative transform from the path to its immediate parent. |
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".
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics. |
matrix | the 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).
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.
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics. |
vertices | is a 3-by-N matrix of 3D point defining the vertices of the mesh. |
faces | is a 3-by-M integer matrix with each entry denoting an index into vertices and each column denoting one face (aka SurfaceTriangle). |
colors | is a 3-by-N matrix of color values, one color per vertex of the mesh. |
wireframe | if "true", then only the triangle edges are visualized, not the faces. |
wireframe_line_width | is the width in pixels. Due to limitations in WebGL implementations, the line width may be 1 regardless of the set value. |
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.
path | a "/"-delimited string indicating the path in the scene tree. See Meshcat paths for the semantics. |
vertices | is a 3-by-N matrix of 3D point defining the vertices of the mesh. |
faces | is a 3-by-M integer matrix with each entry denoting an index into vertices and each column denoting one face (aka SurfaceTriangle). |
rgba | is the mesh face or wireframe color. |
wireframe | if "true", then only the triangle edges are visualized, not the faces. |
wireframe_line_width | is the width in pixels. Due to limitations in WebGL implementations, the line width may be 1 regardless of the set value. |
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.
std::string web_url | ( | ) | const |
Returns the hosted http 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().