Drake
Drake C++ Documentation
drake::visualization Namespace Reference

Classes

struct  VisualizationConfig
 Settings for what MultibodyPlant and SceneGraph should send to meldis and/or drake_visualizer. More...
 

Functions

void ApplyVisualizationConfig (const VisualizationConfig &config, systems::DiagramBuilder< double > *builder, const systems::lcm::LcmBuses *lcm_buses=nullptr, const multibody::MultibodyPlant< double > *plant=nullptr, const geometry::SceneGraph< double > *scene_graph=nullptr, std::shared_ptr< geometry::Meshcat > meshcat=nullptr, lcm::DrakeLcmInterface *lcm=nullptr)
 Adds LCM visualization publishers to communicate to drake_visualizer and/or meldis. More...
 
void AddDefaultVisualization (systems::DiagramBuilder< double > *builder)
 Adds LCM visualization publishers to communicate to drake_visualizer and/or meldis, using all of the default configuration settings. More...
 

Function Documentation

◆ AddDefaultVisualization()

void drake::visualization::AddDefaultVisualization ( systems::DiagramBuilder< double > *  builder)

Adds LCM visualization publishers to communicate to drake_visualizer and/or meldis, using all of the default configuration settings.

Example
// Create a builder.
DiagramBuilder<double> builder;
// Add the MultibodyPlant and SceneGraph.
const MultibodyPlantConfig plant_config = ...;
MultibodyPlant<double>& plant = AddMultibodyPlant(plant_config, &builder);
// ... populate the plant, e.g., with a Parser, ...
plant.Finalize();
// Add the visualization.
// Simulate.
Simulator<double> simulator(builder.Build());
// ... etc ...
Precondition
AddMultibodyPlant() or AddMultibodyPlantSceneGraph() has already been called on the given builder.
The MultibodyPlant in the given builder is already finalized, as in plant.Finalize().
See also
drake::visualization::ApplyVisualizationConfig()
drake::multibody::AddMultibodyPlant()

◆ ApplyVisualizationConfig()

void drake::visualization::ApplyVisualizationConfig ( const VisualizationConfig config,
systems::DiagramBuilder< double > *  builder,
const systems::lcm::LcmBuses lcm_buses = nullptr,
const multibody::MultibodyPlant< double > *  plant = nullptr,
const geometry::SceneGraph< double > *  scene_graph = nullptr,
std::shared_ptr< geometry::Meshcat meshcat = nullptr,
lcm::DrakeLcmInterface lcm = nullptr 
)

Adds LCM visualization publishers to communicate to drake_visualizer and/or meldis.

Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time. The exact function signature is subject to change as we polish this new feature.
Example
// Create a builder.
DiagramBuilder<double> builder;
// Add the MultibodyPlant and SceneGraph.
const MultibodyPlantConfig plant_config = ...;
MultibodyPlant<double>& plant = AddMultibodyPlant(plant_config, &builder);
// ... populate the plant, e.g., with a Parser, ...
plant.Finalize();
// Add the visualization.
const VisualizationConfig vis_config = ...;
ApplyVisualizationConfig(config, &builder);
// Simulate.
Simulator<double> simulator(builder.Build());
// ... etc ...
Parameters
[in]configThe visualization configuration.
[in,out]builderThe diagram to add visualization systems into.
[in]lcm_buses(Optional) The available LCM buses to use for visualization message publication. When not provided, uses the lcm interface if provided, or else the config.lcm_bus must be set to "default" in which case an appropriate drake::lcm::DrakeLcm object is constructed and used internally.
[in]plant(Optional) The MultibodyPlant to visualize. In the common case where a MultibodyPlant has already been added to builder using either AddMultibodyPlant() or AddMultibodyPlantSceneGraph(), the default value (nullptr) here is suitable and generally should be preferred. When provided, it must be a System that's been added to the the given builder. When not provided, visualizes the system named "plant" in the given builder.
[in]scene_graph(Optional) The SceneGraph to visualize. In the common case where a SceneGraph has already been added to builder using either AddMultibodyPlant() or AddMultibodyPlantSceneGraph(), the default value (nullptr) here is suitable and generally should be preferred. When provided, it must be a System that's been added to the the given builder. When not provided, visualizes the system named "scene_graph" in the given builder.
[in]meshcat(Optional) A Meshcat object for visualization message publication. When not provided, a Meshcat object will be created unless config.enable_meshcat_creation is set to false.
[in]lcm(Optional) The LCM interface used for visualization message publication. When not provided, uses the config.lcm_bus value to look up the appropriate interface from lcm_buses.
Precondition
The builder is non-null.
Either the config.lcm_bus is set to "default", or else lcm_buses is non-null and contains a bus named config.lcm_bus, or else lcm is non-null.
Either the given builder contains a MultibodyPlant system named "plant" or else the provided plant is non-null.
Either the given builder contains a SceneGraph system named "scene_graph" or else the provided scene_graph is non-null.
The MultibodyPlant is already finalized, as in plant.Finalize().
See also
drake::visualization::AddDefaultVisualization()
drake::multibody::AddMultibodyPlant()
drake::systems::lcm::ApplyLcmBusConfig()