Drake
Drake C++ Documentation
VisualizationConfig Struct Reference

Detailed Description

Settings for what MultibodyPlant and SceneGraph should send to Meshcat and/or Meldis.

See ApplyVisualizationConfig() for how to enact this configuration.

#include <drake/visualization/visualization_config.h>

Public Member Functions

template<typename Archive >
void Serialize (Archive *a)
 

Public Attributes

std::string lcm_bus {"default"}
 Which LCM URL to use. More...
 
double publish_period {1 / 64.0}
 The duration (in seconds) between published LCM messages that update visualization. More...
 
bool publish_illustration {true}
 Whether to show illustration geometry. More...
 
geometry::Rgba default_illustration_color {0.9, 0.9, 0.9, 1.0}
 The color to apply to any illustration geometry that hasn't defined one. More...
 
bool publish_proximity {true}
 Whether to show proximity geometry. More...
 
geometry::Rgba default_proximity_color {0.8, 0, 0, 1.0}
 The color to apply to any proximity geometry that hasn't defined one. More...
 
double initial_proximity_alpha {0.5}
 The initial value of the proximity alpha slider. More...
 
bool publish_inertia {true}
 Whether to show body inertia. More...
 
bool publish_contacts {true}
 Whether to show contact forces. More...
 
bool enable_meshcat_creation {true}
 Whether to create a Meshcat object if needed. More...
 
bool delete_on_initialization_event {true}
 Determines whether to send a Meshcat::Delete() messages to the Meshcat object (if any) on an initialization event to remove any visualizations, e.g., from a previous simulation. More...
 
bool enable_alpha_sliders {false}
 Determines whether to enable alpha sliders for geometry display. More...
 

Member Function Documentation

◆ Serialize()

void Serialize ( Archive *  a)

Member Data Documentation

◆ default_illustration_color

geometry::Rgba default_illustration_color {0.9, 0.9, 0.9, 1.0}

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

The vector must be of size three (rgb) or four (rgba).

◆ default_proximity_color

geometry::Rgba default_proximity_color {0.8, 0, 0, 1.0}

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

The vector must be of size three (rgb) or four (rgba).

◆ delete_on_initialization_event

bool delete_on_initialization_event {true}

Determines whether to send a Meshcat::Delete() messages to the Meshcat object (if any) on an initialization event to remove any visualizations, e.g., from a previous simulation.

◆ enable_alpha_sliders

bool enable_alpha_sliders {false}

Determines whether to enable alpha sliders for geometry display.

◆ enable_meshcat_creation

bool enable_meshcat_creation {true}

Whether to create a Meshcat object if needed.

◆ initial_proximity_alpha

double initial_proximity_alpha {0.5}

The initial value of the proximity alpha slider.

Note: the effective transparency of the proximity geometry is the slider value multiplied by the alpha value of default_proximity_color. To have access to the full range of opacity, the color's alpha value should be one and the slider should be used to change it.

◆ lcm_bus

std::string lcm_bus {"default"}

Which LCM URL to use.

See also
drake::systems::lcm::LcmBuses

◆ publish_contacts

bool publish_contacts {true}

Whether to show contact forces.

◆ publish_illustration

bool publish_illustration {true}

Whether to show illustration geometry.

◆ publish_inertia

bool publish_inertia {true}

Whether to show body inertia.

◆ publish_period

double publish_period {1 / 64.0}

The duration (in seconds) between published LCM messages that update visualization.

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

◆ publish_proximity

bool publish_proximity {true}

Whether to show proximity geometry.


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