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
The two overloads differ in the following way:
The parameters have the following semantics:
| |||||||||||||
systems::lcm::LcmPublisherSystem * | 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. More... | |||||||||||||
systems::lcm::LcmPublisherSystem * | 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. More... | |||||||||||||
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.
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.