Drake
Drake C++ Documentation
MeshcatVisualizerParams Struct Reference

Detailed Description

The set of parameters for configuring MeshcatVisualizer.

#include <drake/geometry/meshcat_visualizer_params.h>

Public Member Functions

template<typename Archive >
void Serialize (Archive *a)
 Passes this object to an Archive. More...
 

Public Attributes

double publish_period {1 / 64.0}
 The duration (in simulation seconds) between attempts to update poses in the visualizer. More...
 
Role role {Role::kIllustration}
 The role of the geometries to be sent to the visualizer. More...
 
Rgba default_color {0.9, 0.9, 0.9, 1.0}
 The color to apply to any geometry that hasn't defined one. More...
 
std::string prefix {"visualizer"}
 A prefix to add to the path for all objects and transforms curated by the MeshcatVisualizer. More...
 
bool delete_on_initialization_event {true}
 Determines whether to send a Meshcat::Delete(prefix) message on an initialization event to remove any visualizations e.g. More...
 
bool enable_alpha_slider {false}
 Determines whether to enable the alpha slider for geometry display. More...
 
double initial_alpha_slider_value {1.0}
 Initial alpha slider value. More...
 
bool visible_by_default {true}
 Determines whether our meshcat path should be default to being visible. More...
 
bool show_hydroelastic {false}
 When using the hydroelastic contact model, collision geometries that are declared as geometric primitives are frequently represented by some discretely tessellated mesh when computing contact. More...
 
bool include_unspecified_accepting {true}
 (Advanced) For a given geometry, if the GeometryProperties for our role has the property (meshcat, accepting) then the visualizer will show the geometry only if the property's value matches our prefix. More...
 

Member Function Documentation

◆ Serialize()

void Serialize ( Archive *  a)

Passes this object to an Archive.

Refer to YAML Serialization for background.

Member Data Documentation

◆ default_color

Rgba default_color {0.9, 0.9, 0.9, 1.0}

The color to apply to any geometry that hasn't defined one.

◆ delete_on_initialization_event

bool delete_on_initialization_event {true}

Determines whether to send a Meshcat::Delete(prefix) message on an initialization event to remove any visualizations e.g.

from a previous simulation. See Declare initializationevents" for more information.

◆ enable_alpha_slider

bool enable_alpha_slider {false}

Determines whether to enable the alpha slider for geometry display.

◆ include_unspecified_accepting

bool include_unspecified_accepting {true}

(Advanced) For a given geometry, if the GeometryProperties for our role has the property (meshcat, accepting) then the visualizer will show the geometry only if the property's value matches our prefix.

If that property is absent then the geometry will be shown only if include_unspecified_accepting is true.

◆ initial_alpha_slider_value

double initial_alpha_slider_value {1.0}

Initial alpha slider value.

This value should lie in the range [0, 1]. Furthermore, the slider value is quantized which means the value used here will be replaced with the nearest quantized value supported by the slider implementation.

◆ prefix

std::string prefix {"visualizer"}

A prefix to add to the path for all objects and transforms curated by the MeshcatVisualizer.

It can be an absolute path or relative path. If relative, this prefix will be appended to the Meshcat prefix based on the standard path semantics in Meshcat. See Meshcat paths for details.

◆ publish_period

double publish_period {1 / 64.0}

The duration (in simulation seconds) between attempts to update poses in the visualizer.

(To help avoid small simulation time steps, we use a default period that has an exact representation in binary floating point; see drake#15021 for details.)

◆ role

The role of the geometries to be sent to the visualizer.

◆ show_hydroelastic

bool show_hydroelastic {false}

When using the hydroelastic contact model, collision geometries that are declared as geometric primitives are frequently represented by some discretely tessellated mesh when computing contact.

It can be quite helpful in assessing contact behavior to visualize these discrete meshes (in place of the idealized primitives).

To visualize these representations it is necessary to request visualization of geometries with the Role::kProximity role (see the role field). It is further necessary to explicitly request the hydroelastic meshes where available (setting show_hydroelastic to true).

Setting this show_hydroelastic to true will have no apparent effect if none of the collision meshes have a hydroelastic mesh associated with them.

This option is ignored by MeshcatVisualizer<T> when T is not double, e.g. if T == AutoDiffXd.

◆ visible_by_default

bool visible_by_default {true}

Determines whether our meshcat path should be default to being visible.


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