Skip to content

Commit

Permalink
Adds C++17 structured binding support to AddMultibodyPlantSceneGraphR…
Browse files Browse the repository at this point in the history
  • Loading branch information
amcastro-tri authored and jwnimmer-tri committed Jan 14, 2020
1 parent 21d099a commit 40fd5f2
Show file tree
Hide file tree
Showing 3 changed files with 64 additions and 12 deletions.
14 changes: 6 additions & 8 deletions manipulation/models/ycb/test/parse_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,21 +53,19 @@ TEST_P(ParseTest, Quantities) {
"drake/manipulation/models/ycb/sdf/{}.sdf", object_name));

DiagramBuilder<double> builder;
MultibodyPlant<double>* plant{};
SceneGraph<double>* scene_graph{};
std::tie(plant, scene_graph) = AddMultibodyPlantSceneGraph(&builder, 0.0);
Parser(plant).AddModelFromFile(filename);
ConnectDrakeVisualizer(&builder, *scene_graph);
plant->Finalize();
auto[plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, 0.0);
Parser(&plant).AddModelFromFile(filename);
ConnectDrakeVisualizer(&builder, scene_graph);
plant.Finalize();
auto diagram = builder.Build();

// MultibodyPlant always creates at least two model instances, one for the
// world and one for a default model instance for unspecified modeling
// elements. Finally, there is a model instance for each YCB sdf file.
EXPECT_EQ(plant->num_model_instances(), 3);
EXPECT_EQ(plant.num_model_instances(), 3);

// Each object has two bodies, the world body and the object body.
EXPECT_EQ(plant->num_bodies(), 2);
EXPECT_EQ(plant.num_bodies(), 2);

if (FLAGS_visualize_sec > 0.) {
drake::log()->info("Visualize: {}", object_name);
Expand Down
52 changes: 48 additions & 4 deletions multibody/plant/multibody_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -236,11 +236,9 @@ enum class ContactModel {
/// items.plant.DoFoo(...);
/// items.scene_graph.DoBar(...);
/// @endcode
/// or
/// or taking advantage of C++17's structured binding
/// @code
/// auto items = AddMultibodyPlantSceneGraph(&builder, 0.0 /* time_step */);
/// MultibodyPlant<double>& plant = items.plant;
/// SceneGraph<double>& scene_graph = items.scene_graph;
/// auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder);
/// ...
/// plant.DoFoo(...);
/// scene_graph.DoBar(...);
Expand Down Expand Up @@ -4211,6 +4209,20 @@ struct AddMultibodyPlantSceneGraphResult final {
return std::tie(plant_ptr, scene_graph_ptr);
}

#ifndef DRAKE_DOXYGEN_CXX
// Returns the N-th member referenced by this struct.
// If N = 0, returns the reference to the MultibodyPlant.
// If N = 1, returns the reference to the geometry::SceneGraph.
// Provided to support C++17's structured binding.
template <std::size_t N>
decltype(auto) get() const {
if constexpr (N == 0)
return plant;
else if constexpr (N == 1)
return scene_graph;
}
#endif

#ifndef DRAKE_DOXYGEN_CXX
// Only the move constructor is enabled; copy/assign/move-assign are deleted.
AddMultibodyPlantSceneGraphResult(
Expand Down Expand Up @@ -4268,6 +4280,38 @@ void MultibodyPlant<symbolic::Expression>::
} // namespace multibody
} // namespace drake

#ifndef DRAKE_DOXYGEN_CXX
// Specializations provided to support C++17's structured binding for
// AddMultibodyPlantSceneGraphResult.
namespace std {
// The GCC standard library defines tuple_size as class and struct which
// triggers a warning here.
// We found this solution in: https://github.com/nlohmann/json/issues/1401
#if defined(__clang__)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wmismatched-tags"
#endif
template <typename T>
struct tuple_size<drake::multibody::AddMultibodyPlantSceneGraphResult<T>>
: std::integral_constant<std::size_t, 2> {};

template <typename T>
struct tuple_element<0,
drake::multibody::AddMultibodyPlantSceneGraphResult<T>> {
using type = drake::multibody::MultibodyPlant<T>;
};

template <typename T>
struct tuple_element<1,
drake::multibody::AddMultibodyPlantSceneGraphResult<T>> {
using type = drake::geometry::SceneGraph<T>;
};
#if defined(__clang__)
#pragma GCC diagnostic pop
#endif
} // namespace std
#endif

DRAKE_DECLARE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
class drake::multibody::MultibodyPlant)
DRAKE_DECLARE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
Expand Down
10 changes: 10 additions & 0 deletions multibody/plant/test/multibody_plant_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@

#include "drake/common/eigen_autodiff_types.h"
#include "drake/common/find_resource.h"
#include "drake/common/nice_type_name.h"
#include "drake/common/symbolic.h"
#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/common/test_utilities/expect_no_throw.h"
Expand Down Expand Up @@ -332,6 +333,15 @@ GTEST_TEST(MultibodyPlantTest, AddMultibodyPlantSceneGraph) {
MultibodyPlant<double>& plant_ref = pair;
EXPECT_EQ(&plant_ref, plant);

// Check support for C++17's structured binding.
auto[first_element, second_element] =
AddMultibodyPlantSceneGraph(&builder, 0.0);
// Verify the expected types.
EXPECT_EQ(drake::NiceTypeName::Get(first_element),
drake::NiceTypeName::Get<MultibodyPlant<double>>());
EXPECT_EQ(drake::NiceTypeName::Get(second_element),
drake::NiceTypeName::Get<SceneGraph<double>>());

// These should fail:
// AddMultibodyPlantSceneGraphResult<double> extra(plant, scene_graph);
// AddMultibodyPlantSceneGraphResult<double> extra{*plant, *scene_graph};
Expand Down

0 comments on commit 40fd5f2

Please sign in to comment.