Skip to content

Commit

Permalink
Enable drake visualizer to consume new hydro lcm fields
Browse files Browse the repository at this point in the history
This gives the drake_visualizer plugin the power to consume the new
per-body fields in the lcm message: model and geometry names.

Previously, the _Contact class was synonymous with per-body-pair contact.
That is no longer true. A body pair can have multiple contacts. This led
to a refactoring where there is now _BodyContact (all of the contacts
between a pair of bodies) and _Contact (a single contact between body
pairs).

The names displayed in the object model for bodies and contact data now
depend on a GUI configuration. Default behavior is the legacy behavior
(compact, yet possibly ambiguous). Turning it on provides verbose but
unambiguous names all the time.

With this change, the visualizer can now handle multiple contacts per
body pair and distinguish between two bodies with the same name, but in
different model instances.

This incidentally extends simple_contact_surface_vis.cc to populate all of
the new fields in the lcm message to test the visualizer.
  • Loading branch information
SeanCurtis-TRI committed Sep 8, 2021
1 parent 7e815c1 commit 304d502
Show file tree
Hide file tree
Showing 2 changed files with 437 additions and 144 deletions.
63 changes: 53 additions & 10 deletions examples/scene_graph/simple_contact_surface_vis.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
and anchored) and their properties to see the effect on contact surface. */

#include <memory>
#include <unordered_map>

#include <gflags/gflags.h>

Expand Down Expand Up @@ -84,6 +85,12 @@ DEFINE_bool(rigid_cylinders, true,
"hydroelastic representation");
DEFINE_bool(hybrid, false, "Set to true to run hybrid hydroelastic");

/* To help simulate MultibodyPlant; we're going to assign frames "frame groups"
that correlate with MbP's "model instance indices". We're defining the indices
here and defining the look up table in the function that uses it. */
constexpr int kBallModelInstance = 1;
constexpr int kCylinderModelInstance = 2;

/** Places a ball at the world's origin and defines its velocity as being
sinusoidal in time in the z direction.
Expand All @@ -102,8 +109,8 @@ class MovingBall final : public LeafSystem<double> {

// Add geometry for a ball that moves based on sinusoidal derivatives.
source_id_ = scene_graph->RegisterSource("moving_ball");
frame_id_ =
scene_graph->RegisterFrame(source_id_, GeometryFrame("moving_frame"));
frame_id_ = scene_graph->RegisterFrame(
source_id_, GeometryFrame("moving_frame", kBallModelInstance));
geometry_id_ = scene_graph->RegisterGeometry(
source_id_, frame_id_,
make_unique<GeometryInstance>(RigidTransformd(),
Expand Down Expand Up @@ -186,6 +193,15 @@ class ContactResultMaker final : public LeafSystem<double> {
}

private:
static std::string ModelInstanceName(int frame_group) {
const std::unordered_map<int, std::string> kModelInstanceNames(
{{kBallModelInstance, "MovingBall"},
{kCylinderModelInstance, "FixedCylinders"}});
auto iter = kModelInstanceNames.find(frame_group);
if (iter == kModelInstanceNames.end()) return "DefaultModelInstance";
return iter->second;
}

void CalcContactResults(const Context<double>& context,
lcmt_contact_results_for_viz* results) const {
const auto& query_object =
Expand Down Expand Up @@ -213,13 +229,30 @@ class ContactResultMaker final : public LeafSystem<double> {
dest[2] = src(2);
};

const auto& inspector = query_object.inspector();

// Contact surfaces.
for (int i = 0; i < num_surfaces; ++i) {
lcmt_hydroelastic_contact_surface_for_viz& surface_msg =
msg.hydroelastic_contacts[i];

surface_msg.body1_name = "Id_" + to_string(surfaces[i].id_M());
surface_msg.body2_name = "Id_" + to_string(surfaces[i].id_N());
// We'll simulate MbP's model instance/body paradigm. We have a look up
// function to define a model instance. The body name will be the frame
// name as there is a 1-to-1 correspondence between MbP bodies and
// geometry frames. The geometry will use the name stored in SceneGraph.
const GeometryId id1 = surfaces[i].id_M();
const FrameId f_id1 = inspector.GetFrameId(id1);
surface_msg.body1_name = inspector.GetName(f_id1);
surface_msg.model1_name =
ModelInstanceName(inspector.GetFrameGroup(f_id1));
surface_msg.geometry1_name = inspector.GetName(id1);

const GeometryId id2 = surfaces[i].id_N();
const FrameId f_id2 = inspector.GetFrameId(id2);
surface_msg.body2_name = inspector.GetName(inspector.GetFrameId(id2));
surface_msg.model2_name =
ModelInstanceName(inspector.GetFrameGroup(f_id2));
surface_msg.geometry2_name = inspector.GetName(id2);

const SurfaceMesh<double>& mesh_W = surfaces[i].mesh_W();
surface_msg.num_triangles = mesh_W.num_faces();
Expand Down Expand Up @@ -325,15 +358,19 @@ int do_main() {
// Add two cylinders to bang into -- if the rigid_cylinders flag is set to
// false, this should crash in strict hydroelastic mode, but report point
// contact in non-strict mode.
// The purpose of having two cylinders instead of one is to verify that the
// duplicated contact patch visualization issue in #14578 is fixed.

// We provide two cylinders affixed to a single frame to more robustly
// exercise the visualization logic; it allows *two* contacts between the
// double-can "body" and the moving ball.
const FrameId can_frame_id = scene_graph.RegisterFrame(
source_id, GeometryFrame("double_can", kCylinderModelInstance));
const RigidTransformd X_WC1(Vector3d{-0.5, 0, 3});
const RigidTransformd X_WC2(Vector3d{0.5, 0, 3});
const GeometryId can1_id = scene_graph.RegisterAnchoredGeometry(
source_id, make_unique<GeometryInstance>(
const GeometryId can1_id = scene_graph.RegisterGeometry(
source_id, can_frame_id, make_unique<GeometryInstance>(
X_WC1, make_unique<Cylinder>(0.5, 1.0), "can1"));
const GeometryId can2_id = scene_graph.RegisterAnchoredGeometry(
source_id, make_unique<GeometryInstance>(
const GeometryId can2_id = scene_graph.RegisterGeometry(
source_id, can_frame_id, make_unique<GeometryInstance>(
X_WC2, make_unique<Cylinder>(0.5, 1.0), "can2"));
ProximityProperties proximity_cylinder;
if (FLAGS_rigid_cylinders) {
Expand Down Expand Up @@ -367,6 +404,12 @@ int do_main() {
auto diagram = builder.Build();

systems::Simulator<double> simulator(*diagram);
systems::Context<double>& diagram_context = simulator.get_mutable_context();
systems::Context<double>& sg_context =
scene_graph.GetMyMutableContextFromRoot(&diagram_context);
scene_graph.get_source_pose_port(source_id).FixValue(
&sg_context,
geometry::FramePoseVector<double>{{can_frame_id, RigidTransformd{}}});

simulator.get_mutable_integrator().set_maximum_step_size(0.002);
simulator.set_target_realtime_rate(FLAGS_real_time ? 1.f : 0.f);
Expand Down
Loading

0 comments on commit 304d502

Please sign in to comment.