#include <functional>
#include <memory>
#include <optional>
#include <string>
#include <type_traits>
#include <unordered_map>
#include <vector>
#include "drake/common/default_scalars.h"
#include "drake/common/drake_copyable.h"
#include "drake/geometry/geometry_ids.h"
#include "drake/geometry/scene_graph.h"
#include "drake/lcmt_contact_results_for_viz.hpp"
#include "drake/multibody/plant/contact_results.h"
#include "drake/multibody/plant/multibody_plant.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/framework/leaf_system.h"
#include "drake/systems/lcm/lcm_publisher_system.h"
Classes | |
class | ContactResultsToLcmSystem< T > |
A System that encodes ContactResults into a lcmt_contact_results_for_viz message. More... | |
Namespaces | |
drake | |
drake::multibody | |
Functions | |||||||||||||
DRAKE_DECLARE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS (class drake::multibody::ContactResultsToLcmSystem) | |||||||||||||
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... | |||||||||||||
DRAKE_DECLARE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS | ( | class drake::multibody::ContactResultsToLcmSystem | ) |