Drake
Drake C++ Documentation

Detailed Description

Systems for connecting to external visualization tools/GUIs.

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

Classes

class  ContactVisualizer< T >
 ContactVisualizer is a system that publishes a ContactResults to geometry::Meshcat; For point contact results, it draws double-sided arrows at the location of the contact force with length scaled by the magnitude of the contact force. More...
 
class  JointSliders< T >
 JointSliders adds slider bars to the Meshcat control panel for the joints of a MultibodyPlant. More...
 
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...
 
class  ColorizeDepthImage< T >
 ColorizeDepthImage converts a depth image, either 32F or 16U, to a color image. More...
 
class  ColorizeLabelImage< T >
 ColorizeLabelImage converts a label image to a color image. More...
 
class  ConcatenateImages< T >
 ConcatenateImages stacks multiple input images into a single output image. More...
 
class  InertiaVisualizer< T >
 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< T >
 MeshcatPoseSliders adds slider bars to the MeshCat control panel for the roll, pitch, yaw, x, y, z control of a pose. More...
 

Visualizing contact results

These functions extend a Diagram with the required components to publish contact results (as reported by MultibodyPlant) to a visualizer (Meldis). We recommend using these functions instead of assembling the requisite components by hand.

These must be called during Diagram building. Each function makes modifications to the diagram being constructed by builder including the following changes:

  • adds systems multibody::ContactResultsToLcmSystem and LcmPublisherSystem to the Diagram and connects the draw message output to the publisher input,
  • connects a ContactResults<double>-valued output port to the ContactResultsToLcmSystem system, and
  • sets the publishing rate based on publish_period.

The two overloads differ in the following way:

  • One overload takes an OutputPort and one doesn't. This determines what is connected to the ContactResultsToLcmSystem input port. The overload that specifies an OutputPort will attempt to connect that port. The one that doesn't will connect the given plant's contact results output port.

The parameters have the following semantics:

Parameters
builderThe diagram builder being used to construct the Diagram. Systems will be added to this builder.
plantThe System in builder containing the plant whose contact results are to be visualized.
scene_graphThe SceneGraph that will determine how the geometry names will appear in the lcm message.
publish_periodAn optional period to pass along to the LcmPublisherSystem constructor; when null, a reasonable default period will be used.
lcmAn optional lcm interface through which lcm messages will be dispatched. Will be allocated internally if none is supplied. If one is given, it must remain alive at least as long as the diagram built from builder.
contact_results_portThe optional port that will be connected to the ContactResultsToLcmSystem (as documented above).
Returns
(for all overloads) the LcmPublisherSystem (in case callers, e.g., need to change the default publishing rate).
Precondition
plant is contained within the supplied builder.
scene_graph is contained with the supplied builder.
contact_results_port (if given) belongs to a system that is an immediate child of builder.
systems::lcm::LcmPublisherSystemConnectContactResultsToDrakeVisualizer (systems::DiagramBuilder< double > *builder, const MultibodyPlant< double > &plant, const geometry::SceneGraph< double > &scene_graph, lcm::DrakeLcmInterface *lcm=nullptr, std::optional< double > publish_period=std::nullopt)
 MultibodyPlant-connecting overload. More...
 
systems::lcm::LcmPublisherSystemConnectContactResultsToDrakeVisualizer (systems::DiagramBuilder< double > *builder, const MultibodyPlant< double > &plant, const geometry::SceneGraph< double > &scene_graph, const systems::OutputPort< double > &contact_results_port, lcm::DrakeLcmInterface *lcm=nullptr, std::optional< double > publish_period=std::nullopt)
 OutputPort-connecting overload. More...
 

Function Documentation

◆ ConnectContactResultsToDrakeVisualizer() [1/2]

systems::lcm::LcmPublisherSystem* drake::multibody::ConnectContactResultsToDrakeVisualizer ( systems::DiagramBuilder< double > *  builder,
const MultibodyPlant< double > &  plant,
const geometry::SceneGraph< double > &  scene_graph,
lcm::DrakeLcmInterface lcm = nullptr,
std::optional< double publish_period = std::nullopt 
)

MultibodyPlant-connecting overload.

◆ ConnectContactResultsToDrakeVisualizer() [2/2]

systems::lcm::LcmPublisherSystem* drake::multibody::ConnectContactResultsToDrakeVisualizer ( systems::DiagramBuilder< double > *  builder,
const MultibodyPlant< double > &  plant,
const geometry::SceneGraph< double > &  scene_graph,
const systems::OutputPort< double > &  contact_results_port,
lcm::DrakeLcmInterface lcm = nullptr,
std::optional< double publish_period = std::nullopt 
)

OutputPort-connecting overload.