Skip to content

Commit

Permalink
common: Add internal::TypeHash<T> (RobotLocomotion#10718)
Browse files Browse the repository at this point in the history
This soon will be used in AbstractValue to guard downcasts, instead of
comparing the typeinfo objects.  Unlike typeinfo checks, this mechanism
does not have the hazard of falling back to string-comparison slow paths.
  • Loading branch information
jwnimmer-tri authored Feb 20, 2019
1 parent e3e592b commit 18c58bc
Show file tree
Hide file tree
Showing 5 changed files with 315 additions and 8 deletions.
2 changes: 2 additions & 0 deletions common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,7 @@ drake_cc_library(

drake_cc_library(
name = "hash",
srcs = ["hash.cc"],
hdrs = ["hash.h"],
deps = [
":essential",
Expand Down Expand Up @@ -484,6 +485,7 @@ drake_cc_library(
deps = [
":copyable_unique_ptr",
":essential",
":hash",
":is_cloneable",
":nice_type_name",
],
Expand Down
9 changes: 9 additions & 0 deletions common/hash.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#include "drake/common/hash.h"

namespace drake {
namespace internal {

constexpr size_t FNV1aHasher::kFnvPrime;

} // namespace internal
} // namespace drake
18 changes: 13 additions & 5 deletions common/hash.h
Original file line number Diff line number Diff line change
Expand Up @@ -212,34 +212,42 @@ struct uhash {
}
};

namespace detail {
namespace internal {
/// The FNV1a hash algorithm, used for @ref hash_append.
/// https://en.wikipedia.org/wiki/Fowler%E2%80%93Noll%E2%80%93Vo_hash_function
class FNV1aHasher {
public:
using result_type = size_t;

/// Feeds a block of memory into this hash.
void operator()(const void* data, size_t length) noexcept {
const uint8_t* const begin = static_cast<const uint8_t*>(data);
const uint8_t* const end = begin + length;
for (const uint8_t* iter = begin; iter < end; ++iter) {
hash_ = (hash_ ^ *iter) * 1099511628211u;
hash_ = (hash_ ^ *iter) * kFnvPrime;
}
}

explicit operator size_t() noexcept {
/// Feeds a single byte into this hash.
constexpr void add_byte(uint8_t byte) noexcept {
hash_ = (hash_ ^ byte) * kFnvPrime;
}

/// Returns the hash.
explicit constexpr operator size_t() noexcept {
return hash_;
}

private:
static_assert(sizeof(result_type) == (64 / 8), "We require a 64-bit size_t");
result_type hash_{0xcbf29ce484222325u};
static constexpr size_t kFnvPrime = 1099511628211u;
};
} // namespace detail
} // namespace internal

/// The default HashAlgorithm concept implementation across Drake. This is
/// guaranteed to have a result_type of size_t to be compatible with std::hash.
using DefaultHasher = detail::FNV1aHasher;
using DefaultHasher = internal::FNV1aHasher;

/// The default hashing functor, akin to std::hash.
using DefaultHash = drake::uhash<DefaultHasher>;
Expand Down
95 changes: 92 additions & 3 deletions common/test/value_test.cc
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "drake/common/value.h"

#include <functional>
#include <memory>
#include <sstream>
#include <string>
Expand All @@ -12,8 +13,7 @@
#include "drake/systems/framework/test_utilities/my_vector.h"

namespace drake {
namespace systems {
namespace {
namespace test {

// A type with no constructors.
struct BareStruct {
Expand Down Expand Up @@ -66,6 +66,9 @@ struct MoveOrCloneInt {
template <typename T>
bool operator==(int i, const T& value) { return i == value.data; }

using systems::BasicVector;
using systems::MyVector2d;

// Boilerplate for tests that are identical across different types. Our
// TYPED_TESTs will run using all of the below types as the TypeParam.
template <typename TypeParam> class TypedValueTest : public ::testing::Test {};
Expand Down Expand Up @@ -348,6 +351,92 @@ GTEST_TEST(ValueTest, SubclassOfValueSurvivesClone) {
EXPECT_EQ("5,6", printable_erased->print());
}

// Check that TypeHash is extracting exactly the right strings from
// __PRETTY_FUNCTION__.
template <typename T>
void CheckHash(const std::string& name) {
internal::FNV1aHasher hasher;
hasher(name.data(), name.size());
EXPECT_EQ(internal::TypeHash<T>::value, size_t(hasher))
<< " for name\n"
<< " Which is: " << name << "\n"
<< " for __PRETTY_FUNCTION__\n"
<< " Which is: " << __PRETTY_FUNCTION__;
}

namespace {
struct AnonStruct {};
class AnonClass {};
} // namespace
} // namespace systems

#ifdef __APPLE__
constexpr bool kApple = true;
#else
constexpr bool kApple = false;
#endif

GTEST_TEST(TypeHashTest, WellKnownValues) {
// Simple primitives, structs, and classes.
CheckHash<int>("int");
CheckHash<double>("double");
CheckHash<Point>("drake::test::Point");

// Anonymous structs and classes.
CheckHash<AnonStruct>("drake::test::{anonymous}::AnonStruct");
CheckHash<AnonClass>("drake::test::{anonymous}::AnonClass");

// Templated containers without default template arguments.
const std::string stdcc = kApple ? "std::__1" : "std";
CheckHash<std::shared_ptr<double>>(fmt::format(
"{std}::shared_ptr<double>",
fmt::arg("std", stdcc)));
CheckHash<std::pair<int, double>>(fmt::format(
"{std}::pair<int,double>",
fmt::arg("std", stdcc)));

// Templated classes *with* default template arguments.
CheckHash<std::vector<double>>(fmt::format(
"{std}::vector<double,{std}::allocator<double>>",
fmt::arg("std", stdcc)));
CheckHash<std::vector<BasicVector<double>>>(fmt::format(
"{std}::vector<"
"drake::systems::BasicVector<double>,"
"{std}::allocator<drake::systems::BasicVector<double>>"
">", fmt::arg("std", stdcc)));

// Const-qualified types.
CheckHash<std::vector<const double>>(fmt::format(
"{std}::vector<const double,{std}::allocator<const double>>",
fmt::arg("std", stdcc)));
CheckHash<std::shared_ptr<const double>>(fmt::format(
"{std}::shared_ptr<const double>",
fmt::arg("std", stdcc)));

// Eigen classes.
CheckHash<Eigen::VectorXd>("Eigen::Matrix<double,-1,1,0,-1,1>");
CheckHash<Eigen::MatrixXd>("Eigen::Matrix<double,-1,-1,0,-1,-1>");
CheckHash<Eigen::Vector3d>("Eigen::Matrix<double,3,1,0,3,1>");
CheckHash<Eigen::Matrix3d>("Eigen::Matrix<double,3,3,0,3,3>");

// Vectors of Eigens.
CheckHash<std::vector<Eigen::VectorXd>>(fmt::format(
"{std}::vector<{eigen},{std}::allocator<{eigen}>>",
fmt::arg("std", stdcc),
fmt::arg("eigen", "Eigen::Matrix<double,-1,1,0,-1,1>")));

// Everything together at once works.
using BigType = std::vector<std::pair<
const double, std::shared_ptr<Eigen::Matrix3d>>>;
CheckHash<BigType>(fmt::format(
"{std}::vector<"
"{std}::pair<"
"const double,"
"{std}::shared_ptr<Eigen::Matrix<double,3,3,0,3,3>>>,"
"{std}::allocator<{std}::pair<"
"const double,"
"{std}::shared_ptr<Eigen::Matrix<double,3,3,0,3,3>>>>>",
fmt::arg("std", stdcc)));
}

} // namespace test
} // namespace drake
Loading

0 comments on commit 18c58bc

Please sign in to comment.