Skip to content

Commit

Permalink
Renames reinit_after_move -> reset_after_move to match reset_on_copy (R…
Browse files Browse the repository at this point in the history
…obotLocomotion#8219)

* Rename reinit_after_move->reset_after_move to match reset_on_copy.
  • Loading branch information
sherm1 authored and SeanCurtis-TRI committed Mar 2, 2018
1 parent 2680c90 commit 18cd459
Show file tree
Hide file tree
Showing 9 changed files with 50 additions and 51 deletions.
10 changes: 5 additions & 5 deletions common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ drake_cc_library(
":nice_type_name",
":number_traits",
":polynomial",
":reinit_after_move",
":reset_after_move",
":reset_on_copy",
":scoped_singleton",
":sorted_vectors_have_intersection",
Expand Down Expand Up @@ -326,8 +326,8 @@ drake_cc_library(
)

drake_cc_library(
name = "reinit_after_move",
hdrs = ["reinit_after_move.h"],
name = "reset_after_move",
hdrs = ["reset_after_move.h"],
)

drake_cc_library(
Expand Down Expand Up @@ -477,9 +477,9 @@ drake_cc_googletest(
)

drake_cc_googletest(
name = "reinit_after_move_test",
name = "reset_after_move_test",
deps = [
":reinit_after_move",
":reset_after_move",
],
)

Expand Down
27 changes: 13 additions & 14 deletions common/reinit_after_move.h → common/reset_after_move.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,45 +31,44 @@ namespace drake {
///
/// private:
/// std::vector<int> items_;
/// reinit_after_move<int> sum_;
/// reset_after_move<int> sum_;
/// };
/// </pre>
///
/// When moving from `Foo`, the donor object will reset to its default state:
/// `items_` will be empty and `sum_` will be zero. If `Foo` had not used the
/// `reinit_after_move` wrapper, the `sum_` would remain intact (be copied)
/// `reset_after_move` wrapper, the `sum_` would remain intact (be copied)
/// while moving, even though `items_` was cleared.
///
/// @tparam T must support CopyConstructible, CopyAssignable, MoveConstructible,
/// and MoveAssignable and must not throw exceptions during construction or
/// assignment.
/// @see reset_on_copy

// TODO(sherm1) Rename this "reset_after_move".
// TODO(sherm1) Upgrade this to match reset_on_copy (e.g. noexcept).
template <typename T>
class reinit_after_move {
class reset_after_move {
public:
/// Constructs a reinit_after_move<T> with a value-initialized wrapped value.
/// Constructs a reset_after_move<T> with a value-initialized wrapped value.
/// See http://en.cppreference.com/w/cpp/language/value_initialization.
reinit_after_move() {}
reset_after_move() {}

/// Constructs a reinit_after_move<T> with the given wrapped value. This is
/// an implicit conversion, so that reinit_after_move<T> behaves more like
/// Constructs a reset_after_move<T> with the given wrapped value. This is
/// an implicit conversion, so that reset_after_move<T> behaves more like
/// the unwrapped type.
// NOLINTNEXTLINE(runtime/explicit)
reinit_after_move(const T& value) : value_(value) {}
reset_after_move(const T& value) : value_(value) {}

/// @name Implements CopyConstructible, CopyAssignable, MoveConstructible,
/// MoveAssignable.
//@{
reinit_after_move(const reinit_after_move&) = default;
reinit_after_move& operator=(const reinit_after_move&) = default;
reinit_after_move(reinit_after_move&& other) {
reset_after_move(const reset_after_move&) = default;
reset_after_move& operator=(const reset_after_move&) = default;
reset_after_move(reset_after_move&& other) {
value_ = std::move(other.value_);
other.value_ = T{};
}
reinit_after_move& operator=(reinit_after_move&& other) {
reset_after_move& operator=(reset_after_move&& other) {
if (this != &other) {
value_ = std::move(other.value_);
other.value_ = T{};
Expand All @@ -78,7 +77,7 @@ class reinit_after_move {
}
//@}

/// @name Implicit conversion operators to make reinit_after_move<T> act
/// @name Implicit conversion operators to make reset_after_move<T> act
/// as the wrapped type.
//@{
operator T&() { return value_; }
Expand Down
4 changes: 2 additions & 2 deletions common/reset_on_copy.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ namespace drake {
/// source on move doesn't change semantics since the condition of the source
/// after a move is generally undefined. It is instead opportunistic good
/// hygiene for early detection of bugs, taking advantage of the fact that we
/// know type T can be value-initialized. See reinit_after_move for more
/// know type T can be value-initialized. See reset_after_move for more
/// discussion.
///
/// Example:
Expand Down Expand Up @@ -66,7 +66,7 @@ namespace drake {
/// zero, regardless of whether 0 is one of the specified enumeration values.
///
/// @tparam T must satisfy `std::is_scalar<T>`.
/// @see reinit_after_move
/// @see reset_after_move

// NOTE(sherm1) to future implementers: if you decide to extend this adapter for
// use with class types, be sure to think carefully about the semantics of copy
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "drake/common/reinit_after_move.h"
#include "drake/common/reset_after_move.h"

#include <gtest/gtest.h>

Expand All @@ -13,21 +13,21 @@ int ForceInt(int value) {
}

GTEST_TEST(DefaultValueTest, Constructor) {
EXPECT_EQ(reinit_after_move<int>(), 0);
EXPECT_EQ(reinit_after_move<int>(1), 1);
EXPECT_EQ(reset_after_move<int>(), 0);
EXPECT_EQ(reset_after_move<int>(1), 1);
}

GTEST_TEST(DefaultValueTest, Access) {
// Assignment from a RHS of int (versus reinit_after_move<int>).
reinit_after_move<int> x;
// Assignment from a RHS of int (versus reset_after_move<int>).
reset_after_move<int> x;
x = 1;

// Conversion operator, non-const value.
EXPECT_EQ(x, 1);
EXPECT_EQ(ForceInt(x), 1);

// Conversion operator, const.
const reinit_after_move<int>& x_cref = x;
const reset_after_move<int>& x_cref = x;
EXPECT_EQ(x_cref, 1);
EXPECT_EQ(ForceInt(x_cref), 1);

Expand All @@ -54,25 +54,25 @@ struct Thing {
// Check that the dereferencing operators *ptr and ptr-> work for pointer types.
GTEST_TEST(DefaultValueTest, Pointers) {
int i = 5;
reinit_after_move<int*> i_ptr{&i};
reinit_after_move<const int*> i_cptr{&i};
reset_after_move<int*> i_ptr{&i};
reset_after_move<const int*> i_cptr{&i};

EXPECT_EQ(*i_ptr, 5);
EXPECT_EQ(*i_cptr, 5);
*i_ptr = 6;
EXPECT_EQ(*i_ptr, 6);
EXPECT_EQ(*i_cptr, 6);

reinit_after_move<int*> i_ptr2(std::move(i_ptr));
reinit_after_move<const int*> i_cptr2(std::move(i_cptr));
reset_after_move<int*> i_ptr2(std::move(i_ptr));
reset_after_move<const int*> i_cptr2(std::move(i_cptr));
EXPECT_EQ(i_ptr2, &i);
EXPECT_EQ(i_cptr2, &i);
EXPECT_EQ(i_ptr, nullptr);
EXPECT_EQ(i_cptr, nullptr);

Thing thing;
reinit_after_move<Thing*> thing_ptr{&thing};
reinit_after_move<const Thing*> thing_cptr{&thing};
reset_after_move<Thing*> thing_ptr{&thing};
reset_after_move<const Thing*> thing_cptr{&thing};

// Make sure there's no cloning happening.
EXPECT_EQ(&*thing_ptr, &thing);
Expand All @@ -83,27 +83,27 @@ GTEST_TEST(DefaultValueTest, Pointers) {
}

GTEST_TEST(DefaultValueTest, Copy) {
reinit_after_move<int> x{1};
reset_after_move<int> x{1};
EXPECT_EQ(x, 1);

// Copy-construction (from non-const reference) and lack of aliasing.
reinit_after_move<int> y{x};
reset_after_move<int> y{x};
EXPECT_EQ(x, 1);
EXPECT_EQ(y, 1);
x = 2;
EXPECT_EQ(x, 2);
EXPECT_EQ(y, 1);

// Copy-construction (from const reference) and lack of aliasing.
const reinit_after_move<int>& x_cref = x;
reinit_after_move<int> z{x_cref};
const reset_after_move<int>& x_cref = x;
reset_after_move<int> z{x_cref};
x = 3;
EXPECT_EQ(x, 3);
EXPECT_EQ(y, 1);
EXPECT_EQ(z, 2);

// Copy-assignment and lack of aliasing.
reinit_after_move<int> w{22};
reset_after_move<int> w{22};
w = x;
EXPECT_EQ(x, 3);
EXPECT_EQ(w, 3);
Expand All @@ -114,30 +114,30 @@ GTEST_TEST(DefaultValueTest, Copy) {

// We need to indirect self-move-assign through this function; doing it
// directly in the test code generates a compiler warning.
void MoveAssign(reinit_after_move<int>* target, reinit_after_move<int>* donor) {
void MoveAssign(reset_after_move<int>* target, reset_after_move<int>* donor) {
*target = std::move(*donor);
}

GTEST_TEST(DefaultValueTest, Move) {
reinit_after_move<int> x{1};
reset_after_move<int> x{1};
EXPECT_EQ(x, 1);

// Move-construction and lack of aliasing.
reinit_after_move<int> y{std::move(x)};
reset_after_move<int> y{std::move(x)};
EXPECT_EQ(x, 0);
EXPECT_EQ(y, 1);
x = 2;
EXPECT_EQ(x, 2);
EXPECT_EQ(y, 1);

// Second move-construction and lack of aliasing.
reinit_after_move<int> z{std::move(x)};
reset_after_move<int> z{std::move(x)};
EXPECT_EQ(x, 0);
EXPECT_EQ(y, 1);
EXPECT_EQ(z, 2);

// Move-assignment and lack of aliasing.
reinit_after_move<int> w{22};
reset_after_move<int> w{22};
x = 3;
w = std::move(x);
EXPECT_EQ(x, 0);
Expand Down
2 changes: 1 addition & 1 deletion solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ drake_cc_library(
hdrs = ["solver_id.h"],
deps = [
"//common:essential",
"//common:reinit_after_move",
"//common:reset_after_move",
],
)

Expand Down
4 changes: 2 additions & 2 deletions solvers/solver_id.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include <string>

#include "drake/common/drake_copyable.h"
#include "drake/common/reinit_after_move.h"
#include "drake/common/reset_after_move.h"

namespace drake {
namespace solvers {
Expand Down Expand Up @@ -33,7 +33,7 @@ class SolverId {
friend bool operator!=(const SolverId&, const SolverId&);
friend struct std::less<SolverId>;

reinit_after_move<int> id_;
reset_after_move<int> id_;
std::string name_;
};

Expand Down
2 changes: 1 addition & 1 deletion systems/sensors/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ drake_cc_library(
],
deps = [
"//common:essential",
"//common:reinit_after_move",
"//common:reset_after_move",
"//common:symbolic",
],
)
Expand Down
6 changes: 3 additions & 3 deletions systems/sensors/image.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/reinit_after_move.h"
#include "drake/common/reset_after_move.h"
#include "drake/systems/sensors/pixel_types.h"

namespace drake {
Expand Down Expand Up @@ -145,8 +145,8 @@ class Image {
}

private:
reinit_after_move<int> width_;
reinit_after_move<int> height_;
reset_after_move<int> width_;
reset_after_move<int> height_;
std::vector<T> data_;
};

Expand Down
2 changes: 1 addition & 1 deletion tools/install/libdrake/build_components.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ LIBDRAKE_COMPONENTS = [
"//common:nice_type_name",
"//common:number_traits",
"//common:polynomial",
"//common:reinit_after_move",
"//common:reset_after_move",
"//common:reset_on_copy",
"//common:scoped_singleton",
"//common:sorted_pair",
Expand Down

0 comments on commit 18cd459

Please sign in to comment.