Drake
Drake C++ Documentation
Loading...
Searching...
No Matches
drake::visualization Namespace Reference

Classes

class  ColorizeDepthImage
 ColorizeDepthImage converts a depth image, either 32F or 16U, to a color image. More...
class  ColorizeLabelImage
 ColorizeLabelImage converts a label image to a color image. More...
class  ConcatenateImages
 ConcatenateImages stacks multiple input images into a single output image. More...
class  InertiaVisualizer
 InertiaVisualizer provides illustration geometry to reflect the equivalent inertia of all bodies in a MultibodyPlant that are not welded to the world. More...
class  MeshcatPoseSliders
 MeshcatPoseSliders adds slider bars to the MeshCat control panel for the roll, pitch, yaw, x, y, z control of a pose. More...
struct  VisualizationConfig
 Settings for what MultibodyPlant and SceneGraph should send to Meshcat and/or Meldis. More...

Functions

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

Function Documentation

◆ AddDefaultVisualization()

void AddDefaultVisualization ( systems::DiagramBuilder< double > * builder,
std::shared_ptr< geometry::Meshcat > meshcat = nullptr )

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

Parameters
meshcatAn optional existing Meshcat instance. (If nullptr, then a meshcat instance will be created.)
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 ...
void AddDefaultVisualization(systems::DiagramBuilder< double > *builder, std::shared_ptr< geometry::Meshcat > meshcat=nullptr)
Adds LCM visualization publishers to communicate to Meshcat and/or Meldis, using all of the default c...
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 ApplyVisualizationConfig ( const VisualizationConfig & config,
systems::DiagramBuilder< double > * builder,
const systems::lcm::LcmBuses * lcm_buses = nullptr,
const multibody::MultibodyPlant< double > * plant = nullptr,
geometry::SceneGraph< double > * scene_graph = nullptr,
std::shared_ptr< geometry::Meshcat > meshcat = nullptr,
lcm::DrakeLcmInterface * lcm = nullptr )

Adds LCM visualization publishers to communicate to Meshcat and/or Meldis.

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(vis_config, &builder);
// Simulate.
Simulator<double> simulator(builder.Build());
// ... etc ...
void ApplyVisualizationConfig(const VisualizationConfig &config, systems::DiagramBuilder< double > *builder, const systems::lcm::LcmBuses *lcm_buses=nullptr, const multibody::MultibodyPlant< double > *plant=nullptr, geometry::SceneGraph< double > *scene_graph=nullptr, std::shared_ptr< geometry::Meshcat > meshcat=nullptr, lcm::DrakeLcmInterface *lcm=nullptr)
Adds LCM visualization publishers to communicate to Meshcat and/or Meldis.
Settings for what MultibodyPlant and SceneGraph should send to Meshcat and/or Meldis.
Definition visualization_config.h:17
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()