Skip to content

Commit

Permalink
[common] DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN detects mis-uses
Browse files Browse the repository at this point in the history
Fix various faulty code that is broken by the new detection.
Add unit test advice to document and complement the new checking.
Upgrade yaml_node_test with an example of testing for move efficiency.
  • Loading branch information
jwnimmer-tri committed Oct 9, 2021
1 parent 9606d1d commit 3045cf1
Show file tree
Hide file tree
Showing 10 changed files with 83 additions and 45 deletions.
1 change: 1 addition & 0 deletions common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -864,6 +864,7 @@ drake_cc_googletest(
drake_cc_googletest(
name = "sorted_pair_test",
deps = [
":copyable_unique_ptr",
":sorted_pair",
],
)
Expand Down
24 changes: 19 additions & 5 deletions common/drake_copyable.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,14 +53,28 @@ class Foo {
// ...
};
</pre>
The macro contains a built-in self-check that copy-assignment is well-formed.
This self-check proves that the Classname is CopyConstructible, CopyAssignable,
MoveConstructible, and MoveAssignable (in all but the most arcane cases where a
member of the Classname is somehow CopyAssignable but not CopyConstructible).
Therefore, classes that use this macro typically will not need to have any unit
tests that check for the presence nor correctness of these functions.
However, the self-check does not provide any checks of the runtime efficiency
of the functions. If it is important for performance that the move functions
actually move (instead of making a copy), then you should consider capturing
that in a unit test.
*/
#define DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Classname) \
Classname(const Classname&) = default; \
Classname& operator=(const Classname&) = default; \
Classname(Classname&&) = default; \
Classname& operator=(Classname&&) = default; \
/* Fails at compile-time if default-copy doesn't work. */ \
static void DRAKE_COPYABLE_DEMAND_COPY_CAN_COMPILE() { \
(void) static_cast<Classname& (Classname::*)( \
const Classname&)>(&Classname::operator=); \
}
/* Fails at compile-time if copy-assign doesn't compile. */ \
static void DrakeDefaultCopyAndMoveAndAssign_DoAssign( \
Classname* a, const Classname& b) { *a = b; } \
static_assert( \
&DrakeDefaultCopyAndMoveAndAssign_DoAssign == \
&DrakeDefaultCopyAndMoveAndAssign_DoAssign, \
"The given Classname is not default copy-asignable.");
2 changes: 1 addition & 1 deletion common/name_value.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ namespace drake {
template <typename T>
class NameValue {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(NameValue)
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(NameValue)

/// Type of the referenced value.
typedef T value_type;
Expand Down
2 changes: 1 addition & 1 deletion common/sorted_pair.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ namespace drake {
/// pairs of objects.
///
/// @tparam T A template type that provides `operator<` and supports default
/// construction.
/// construction, copy construction, and copy-assignment.
template <class T>
struct SortedPair {
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(SortedPair)
Expand Down
14 changes: 8 additions & 6 deletions common/test/sorted_pair_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@

#include <gtest/gtest.h>

#include "drake/common/copyable_unique_ptr.h"

namespace drake {
namespace {

Expand Down Expand Up @@ -47,15 +49,15 @@ GTEST_TEST(SortedPair, Set) {

// Verifies that the move assignment operator and move constructor work.
GTEST_TEST(SortedPair, Move) {
auto a = std::make_unique<int>(2);
auto b = std::make_unique<int>(1);
SortedPair<std::unique_ptr<int>> y(std::move(a), std::move(b));
SortedPair<std::unique_ptr<int>> x;
copyable_unique_ptr<int> a(2);
copyable_unique_ptr<int> b(1);
SortedPair<copyable_unique_ptr<int>> y(std::move(a), std::move(b));
SortedPair<copyable_unique_ptr<int>> x;
x = std::move(y);
EXPECT_TRUE(x.first() < x.second());
EXPECT_EQ(y.first().get(), nullptr);
EXPECT_EQ(y.second().get(), nullptr);
y = SortedPair<std::unique_ptr<int>>(std::move(x));
y = SortedPair<copyable_unique_ptr<int>>(std::move(x));
EXPECT_TRUE(y.first() < y.second());
EXPECT_EQ(x.first().get(), nullptr);
EXPECT_EQ(x.second().get(), nullptr);
Expand Down Expand Up @@ -108,7 +110,7 @@ GTEST_TEST(SortedPair, Hash) {

// Checks expansion with STL vector.
GTEST_TEST(SortedPair, VectorExp) {
std::vector<std::unique_ptr<SortedPair<int>>> v;
std::vector<copyable_unique_ptr<SortedPair<int>>> v;
v.emplace_back(std::make_unique<SortedPair<int>>(1, 2));
v.resize(v.capacity() + 1);
EXPECT_EQ(v.front()->first(), 1);
Expand Down
1 change: 1 addition & 0 deletions common/yaml/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,7 @@ drake_cc_googletest(
deps = [
":yaml_node",
"//common/test_utilities:expect_throws_message",
"//common/test_utilities:limit_malloc",
],
)

Expand Down
45 changes: 27 additions & 18 deletions common/yaml/test/yaml_node_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include <gtest/gtest.h>

#include "drake/common/test_utilities/expect_throws_message.h"
#include "drake/common/test_utilities/limit_malloc.h"

namespace drake {
namespace yaml {
Expand All @@ -30,24 +31,6 @@ GTEST_TEST(YamlNodeTest, DefaultConstructor) {
EXPECT_EQ(dut.GetScalar(), "");
}

// Sanity check of defaulted operators. We don't need to test them
// exhaustively, because they are defaulted.
GTEST_TEST(YamlNodeTest, DefaultCopyMove) {
Node dut = Node::MakeScalar("foo");

// Copy constructor.
Node foo(dut);
EXPECT_EQ(dut.GetScalar(), "foo");
EXPECT_EQ(foo.GetScalar(), "foo");

// Move constructor.
Node bar(std::move(dut));
EXPECT_EQ(bar.GetScalar(), "foo");
// It is important for performance that the move constructor actually moves
// the stored data, instead of copying it.
EXPECT_EQ(dut.GetScalar(), "");
}

// Parameterize the remainder of the tests across the three possible types.
using Param = std::tuple<NodeType, std::string_view>;
class YamlNodeParamaterizedTest : public testing::TestWithParam<Param> {
Expand Down Expand Up @@ -125,6 +108,32 @@ TEST_P(YamlNodeParamaterizedTest, GetSetTag) {
EXPECT_EQ(dut.GetTag(), "tag");
}

// It is important for our YAML subsystem performance that the Node's move
// operations actually move the stored data, instead of copying it.
TEST_P(YamlNodeParamaterizedTest, EfficientMoveConstructor) {
Node dut = MakeNonEmptyDut();

auto guard = std::make_unique<test::LimitMalloc>();
Node foo(std::move(dut));
guard.reset();

EXPECT_EQ(dut, MakeEmptyDut());
EXPECT_EQ(foo, MakeNonEmptyDut());
}

// Ditto per the prior test case.
TEST_P(YamlNodeParamaterizedTest, EfficientMoveAssignment) {
Node dut = MakeNonEmptyDut();
Node foo;

auto guard = std::make_unique<test::LimitMalloc>();
foo = std::move(dut);
guard.reset();

EXPECT_EQ(dut, MakeEmptyDut());
EXPECT_EQ(foo, MakeNonEmptyDut());
}

// Check (non-)equality as affected by the stored type of empty nodes.
TEST_P(YamlNodeParamaterizedTest, EqualityPerType) {
Node dut = MakeEmptyDut();
Expand Down
31 changes: 21 additions & 10 deletions geometry/proximity/bvh.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include <variant>
#include <vector>

#include "drake/common/copyable_unique_ptr.h"
#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/eigen_types.h"
Expand Down Expand Up @@ -41,6 +42,8 @@ struct MeshTraits<VolumeMesh<T>> {
template <class BvType, class MeshType>
class BvNode {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(BvNode)

static constexpr int kMaxElementPerLeaf =
MeshTraits<MeshType>::kMaxElementPerBvhLeaf;

Expand All @@ -67,8 +70,6 @@ class BvNode {
: bv_(std::move(bv)),
child_(NodeChildren(std::move(left), std::move(right))) {}

DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(BvNode)

/* Returns the bounding volume. */
const BvType& bv() const { return bv_; }

Expand Down Expand Up @@ -148,21 +149,31 @@ class BvNode {
BvType& bv() { return bv_; }

struct NodeChildren {
std::unique_ptr<BvNode<BvType, MeshType>> left;
std::unique_ptr<BvNode<BvType, MeshType>> right;

NodeChildren(std::unique_ptr<BvNode<BvType, MeshType>> left_in,
std::unique_ptr<BvNode<BvType, MeshType>> right_in)
NodeChildren(std::unique_ptr<BvNode> left_in,
std::unique_ptr<BvNode> right_in)
: left(std::move(left_in)), right(std::move(right_in)) {
DRAKE_DEMAND(left != nullptr);
DRAKE_DEMAND(right != nullptr);
DRAKE_DEMAND(left != right);
}

// TODO(jwnimmer-tri) We should use copyable_unique_ptr here, but the
// dependency cycle of BvNode <=> NodeChildren somehow defeats us.
NodeChildren(const NodeChildren& other)
: NodeChildren{
std::make_unique<BvNode<BvType, MeshType>>(*other.left),
std::make_unique<BvNode<BvType, MeshType>>(*other.right)} {}
: left(std::make_unique<BvNode>(*other.left)),
right(std::make_unique<BvNode>(*other.right)) {}
NodeChildren& operator=(const NodeChildren& other) {
if (this != &other) {
left = std::make_unique<BvNode>(*other.left);
right = std::make_unique<BvNode>(*other.right);
}
return *this;
}
NodeChildren(NodeChildren&& other) = default;
NodeChildren& operator=(NodeChildren&& other) = default;

std::unique_ptr<BvNode> left;
std::unique_ptr<BvNode> right;
};

BvType bv_;
Expand Down
4 changes: 2 additions & 2 deletions multibody/fixed_fem/dev/dirichlet_boundary_condition.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ namespace fem {
template <class T>
class DirichletBoundaryCondition {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(DirichletBoundaryCondition);
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(DirichletBoundaryCondition);

/* Constructs a new %DirichletBoundaryCondition that applies to an FEM model
that has the given `ode_order`. */
Expand Down Expand Up @@ -131,7 +131,7 @@ class DirichletBoundaryCondition {

/* The ODE order of the FemModel that `this` DirichletBoundaryCondition
applies to. */
const int ode_order_;
const int ode_order_{};
};
} // namespace fem
} // namespace multibody
Expand Down
4 changes: 2 additions & 2 deletions solvers/test/second_order_cone_program_examples.h
Original file line number Diff line number Diff line change
Expand Up @@ -260,7 +260,7 @@ void SolveAndCheckSmallestEllipsoidCoveringProblems(
template <int Dim>
class MinimalDistanceFromSphereProblem {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(MinimalDistanceFromSphereProblem);
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(MinimalDistanceFromSphereProblem);

/** @param with_linear_cost If set to true, we add the quadratic cost as the
* sum of a quadratic and a linear cost. Otherwise we add it as a single
Expand Down Expand Up @@ -317,7 +317,7 @@ class MinimalDistanceFromSphereProblem {
Eigen::Matrix<symbolic::Variable, Dim, 1> x_;
Eigen::Matrix<double, Dim, 1> pt_;
Eigen::Matrix<double, Dim, 1> center_;
double radius_;
double radius_{};
};

void TestSocpDualSolution1(const SolverInterface& solver,
Expand Down

0 comments on commit 3045cf1

Please sign in to comment.