Drake

Classes

class  ContactResultsToLcmSystem< T >
 A System that encodes ContactResults into a lcmt_contact_results_for_viz message. More...
 
class  MultibodyPositionToGeometryPose< T >
 A direct-feedthrough system that converts a vector of joint positions directly to a geometry::FramePoseVector<T> to behave like a MultibodyPlant::get_geometry_pose_output_port(). More...
 

Functions

systems::lcm::LcmPublisherSystemConnectDrakeVisualizer (systems::DiagramBuilder< double > *builder, const SceneGraph< double > &scene_graph, lcm::DrakeLcmInterface *lcm=nullptr)
 Extends a Diagram with the required components to interface with drake_visualizer. More...
 
systems::lcm::LcmPublisherSystemConnectContactResultsToDrakeVisualizer (systems::DiagramBuilder< double > *builder, const MultibodyPlant< double > &multibody_plant, lcm::DrakeLcmInterface *lcm=nullptr)
 Extends a Diagram with the required components to publish contact results to drake_visualizer. More...
 
systems::lcm::LcmPublisherSystemConnectContactResultsToDrakeVisualizer (systems::DiagramBuilder< double > *builder, const MultibodyPlant< double > &multibody_plant, const systems::OutputPort< double > &contact_results_port, lcm::DrakeLcmInterface *lcm=nullptr)
 Implements ConnectContactResultsToDrakeVisualizer, but using contact_results_port to explicitly specify the output port used to get contact results for multibody_plant. More...
 

Detailed Description

Systems for connecting to external visualization tools/GUIs.

There are also a number of external projects that provide additional visualization hook=ups:

Function Documentation

◆ ConnectContactResultsToDrakeVisualizer() [1/2]

systems::lcm::LcmPublisherSystem * ConnectContactResultsToDrakeVisualizer ( systems::DiagramBuilder< double > *  builder,
const MultibodyPlant< double > &  multibody_plant,
lcm::DrakeLcmInterface lcm = nullptr 
)

Extends a Diagram with the required components to publish contact results to drake_visualizer.

This must be called during Diagram building and uses the given builder to add relevant subsystems and connections.

This is a convenience method to simplify some common boilerplate for adding contact results visualization capability to a Diagram. What it does is:

  • adds systems ContactResultsToLcmSystem and LcmPublisherSystem to the Diagram and connects the draw message output to the publisher input,
  • connects the multibody_plant contact results output to the ContactResultsToLcmSystem system, and
  • sets the publishing rate to 1/60 of a second (simulated time).
Parameters
builderThe diagram builder being used to construct the Diagram.
multibody_plantThe System in builder containing the plant whose contact results are to be visualized.
lcmAn optional lcm interface through which lcm messages will be dispatched. Will be allocated internally if none is supplied.
Precondition
The given multibody_plant must be contained within the supplied DiagramBuilder.
Returns
the LcmPublisherSystem (in case callers, e.g., need to change the default publishing rate).

◆ ConnectContactResultsToDrakeVisualizer() [2/2]

systems::lcm::LcmPublisherSystem * ConnectContactResultsToDrakeVisualizer ( systems::DiagramBuilder< double > *  builder,
const MultibodyPlant< double > &  multibody_plant,
const systems::OutputPort< double > &  contact_results_port,
lcm::DrakeLcmInterface lcm = nullptr 
)

Implements ConnectContactResultsToDrakeVisualizer, but using contact_results_port to explicitly specify the output port used to get contact results for multibody_plant.

This is required, for instance, when the MultibodyPlant is inside a Diagram, and the Diagram exports the pose bundle port.

Precondition
contact_results_port must be connected to the contact_results_port of multibody_plant.
See also
ConnectContactResultsToDrakeVisualizer().

◆ ConnectDrakeVisualizer()

systems::lcm::LcmPublisherSystem * ConnectDrakeVisualizer ( systems::DiagramBuilder< double > *  builder,
const SceneGraph< double > &  scene_graph,
lcm::DrakeLcmInterface lcm = nullptr 
)

Extends a Diagram with the required components to interface with drake_visualizer.

This must be called during Diagram building and uses the given builder to add relevant subsystems and connections.

This is a convenience method to simplify some common boilerplate for adding visualization capability to a Diagram. What it does is:

  • adds an initialization event that sends the required load message to set up the visualizer with the relevant geometry,
  • adds systems PoseBundleToDrawMessage and LcmPublisherSystem to the Diagram and connects the draw message output to the publisher input,
  • connects the scene_graph pose bundle output to the PoseBundleToDrawMessage system, and
  • sets the publishing rate to 1/60 of a second (simulated time).

The visualization mechanism depends on the illustration role (see Geometry Roles for details). Specifically, only geometries with the illustration role assigned will be included. The visualization function looks for the following properties in the IllustrationProperties instance.

Group name Required Property Name Property Type Property Description
phong no diffuse Eigen::Vector4d The rgba value of the object surface

See MakeDrakeVisualizerProperties() to facilitate making a compliant set of illustration properties.

You can then connect source output ports for visualization like this:

builder->Connect(pose_output_port,
scene_graph.get_source_pose_port(source_id));
Note
The initialization event occurs when Simulator::Initialize() is called (explicitly or implicitly at the start of a simulation). If you aren't going to be using a Simulator, use DispatchLoadMessage() to send the message yourself.
Parameters
builderThe diagram builder being used to construct the Diagram.
scene_graphThe System in builder containing the geometry to be visualized.
lcmAn optional lcm interface through which lcm messages will be dispatched. Will be allocated internally if none is supplied.
Precondition
This method has not been previously called while building the builder's current Diagram.
The given scene_graph must be contained within the supplied DiagramBuilder.
Returns
the LcmPublisherSystem (in case callers, e.g., need to change the default publishing rate).
See also
geometry::DispatchLoadMessage()