Skip to content

Commit

Permalink
Add type_pack meta-programming utilities.
Browse files Browse the repository at this point in the history
  • Loading branch information
EricCousineau-TRI committed Jan 5, 2018
1 parent 1530b72 commit 9a0863b
Show file tree
Hide file tree
Showing 3 changed files with 334 additions and 0 deletions.
14 changes: 14 additions & 0 deletions bindings/pydrake/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ load("@drake//tools/install:install.bzl", "install")
load("//tools/lint:lint.bzl", "add_lint_tests")
load(
"//tools:drake.bzl",
"drake_cc_googletest",
"drake_cc_library",
)
load(
Expand All @@ -29,6 +30,11 @@ package(default_visibility = adjust_labels_for_drake_hoist([

# N.B. Any common headers should be shared via a HEADER ONLY library.

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

# Target Naming Conventions:
# `*_py`
# A Python library (can be pure Python or pybind)
Expand Down Expand Up @@ -160,6 +166,14 @@ drake_py_library(
deps = PYBIND_LIBRARIES + PY_LIBRARIES,
)

drake_cc_googletest(
name = "type_pack_test",
deps = [
":type_pack",
"//common:nice_type_name",
],
)

# Test ODR (One Definition Rule).
drake_pybind_library(
name = "odr_test_module_py",
Expand Down
121 changes: 121 additions & 0 deletions bindings/pydrake/test/type_pack_test.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,121 @@
#include "drake/bindings/pydrake/type_pack.h"

#include <string>
#include <vector>

#include <gtest/gtest.h>

#include "drake/common/nice_type_name.h"

using std::string;
using std::vector;

namespace drake {
namespace {

template <typename... Ts>
struct SimpleTemplate {};

using Pack = type_pack<int, double, char, void>;

// Mostly, this just checks for compilation failures.
GTEST_TEST(TypeUtilTest, TypeAt) {
using T_0 = type_at<0, int, double, char, void>::type;
EXPECT_TRUE((std::is_same<T_0, int>::value));
using T_1 = type_at<1, int, double, char, void>::type;
EXPECT_TRUE((std::is_same<T_1, double>::value));
using T_2 = type_at<2, int, double, char, void>::type;
EXPECT_TRUE((std::is_same<T_2, char>::value));
using T_3 = type_at<3, int, double, char, void>::type;
EXPECT_TRUE((std::is_same<T_3, void>::value));

EXPECT_TRUE((std::is_same<Pack::type_at<0>, int>::value));
EXPECT_TRUE((std::is_same<Pack::type_at<1>, double>::value));
EXPECT_TRUE((std::is_same<Pack::type_at<2>, char>::value));
EXPECT_TRUE((std::is_same<Pack::type_at<3>, void>::value));
}

GTEST_TEST(TypeUtilTest, TypeTags) {
// Ensure that we can default-construct tags for types that are not
// default-constructible.
auto tag_check = type_tag<void>{};
EXPECT_TRUE((std::is_same<
decltype(tag_check), type_tag<void>>::value));
auto pack_check_empty = type_pack<>{};
EXPECT_TRUE((std::is_same<
decltype(pack_check_empty), type_pack<>>::value));
auto pack_check = type_pack<void, void>{};
EXPECT_TRUE((std::is_same<
decltype(pack_check), type_pack<void, void>>::value));
}

GTEST_TEST(TypeUtilTest, Bind) {
using T_0 = Pack::bind<SimpleTemplate>;
EXPECT_TRUE((std::is_same<
T_0, SimpleTemplate<int, double, char, void>>::value));
Pack pack;
using T_1 = decltype(type_bind<SimpleTemplate>(pack));
EXPECT_TRUE((std::is_same<
T_1, SimpleTemplate<int, double, char, void>>::value));
}

GTEST_TEST(TypeUtilTest, Extract) {
using T = SimpleTemplate<int, double, char, void>;
using TPack = type_pack_extract<T>;
EXPECT_TRUE((std::is_same<TPack, Pack>::value));
}

GTEST_TEST(TypeUtilTest, Visit) {
using PackTags = type_pack<
type_tag<int>, type_tag<double>, type_tag<char>, type_tag<void>>;
vector<string> names;
const vector<string> names_expected = {"int", "double", "char", "void"};

auto visitor = [&names](auto tag) {
using T = typename decltype(tag)::type;
names.push_back(NiceTypeName::Get<T>());
};
names.clear();
type_visit(visitor, PackTags{});
EXPECT_EQ(names, names_expected);

names.clear();
type_visit<type_visit_with_tag<>>(visitor, Pack{});
EXPECT_EQ(names, names_expected);

// N.B. `Check` will operate types contained within the pack as dictated by
// the `VisitWith` parameter in `type_visit`.
// As an example, see below that the two visit calls will be visiting the
// same types (with the same results), but `Check` will operate on
// (a) the direct types with `type_visit_with_tag<>` and (b) the tag types
// with `type_visit_with_default` (the default parameter).
const vector<string> names_expected_sub = {"int", "char", "void"};

names.clear();
type_visit<type_visit_with_tag<>, type_check_different_from<double>::type>(
visitor, Pack{});
EXPECT_EQ(names, names_expected_sub);

names.clear();
type_visit(visitor, PackTags{},
template_tag<type_check_different_from<type_tag<double>>::type>{});
EXPECT_EQ(names, names_expected_sub);
};

GTEST_TEST(TypeUtilTest, Transform) {
auto seq = sequence_transform(
constant_add<int, 5>{}, std::make_integer_sequence<int, 5>{});
EXPECT_TRUE((std::is_same<
decltype(seq), std::integer_sequence<int, 5, 6, 7, 8, 9>>::value));
}

GTEST_TEST(TypeUtilTest, Hash) {
using T = int;
using U = int;
using V = double;
EXPECT_EQ(type_hash<T>(), type_hash<U>());
EXPECT_NE(type_hash<T>(), type_hash<V>());
}

} // namespace
} // namespace drake
199 changes: 199 additions & 0 deletions bindings/pydrake/type_pack.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,199 @@
#pragma once

/// @file
/// Basic meta-programming utilities for types, focused on template parameter
/// packs.

#include <cstddef>
#include <type_traits>
#include <typeindex>
#include <typeinfo>
#include <utility>

namespace drake {

template <typename ... Ts>
struct type_pack;

namespace detail {

// Provides type at given index.
template <size_t N, size_t K, typename T, typename ... Ts>
struct type_at_impl {
using type = typename type_at_impl<N, K + 1, Ts...>::type;
};

// Base case.
template <size_t N, typename T, typename ... Ts>
struct type_at_impl<N, N, T, Ts...> {
using type = T;
};

// Visits a type given a VisitWith mechanism, templated to permit
// conditional execution.
template <typename VisitWith, typename Visitor>
struct type_visit_impl {
template <typename T, bool execute>
struct runner {
inline static void run(Visitor&& visitor) {
VisitWith::template run<T>(std::forward<Visitor>(visitor));
}
};
template <typename T>
struct runner<T, false> {
inline static void run(Visitor&&) {}
};
};

// Catches non-template types explicitly.
template <typename T>
struct type_pack_extract_impl {
// Defer to show that this is a bad instantiation.
static_assert(!std::is_same<T, T>::value, "Wrong template");
};

template <template <typename ... Ts> class Tpl, typename ... Ts>
struct type_pack_extract_impl<Tpl<Ts...>> {
using type = type_pack<Ts...>;
};

// Provides type for pack expansion into an initializer list for
// deterministic execution order.
using DummyList = bool[];

template <typename T>
struct assert_default_constructible {
static_assert(std::is_default_constructible<T>::value,
"Must be default constructible");
};

} // namespace detail


/// Extracts the Ith type from a sequence of types.
template <size_t I, typename ... Ts>
struct type_at {
static_assert(I >= 0 && I < sizeof...(Ts), "Invalid type index");
using type = typename detail::type_at_impl<I, 0, Ts...>::type;
};

/// Provides a tag to pass a type for ease of inference.
template <typename T>
struct type_tag {
using type = T;
};

// @note Cannot bind templates with parameters packs arbitrarily.
template <template <typename> class Tpl>
struct template_tag {
template <typename T>
using type = Tpl<T>;
};

/// Provides a tag to pass a parameter packs for ease of inference.
template <typename ... Ts>
struct type_pack {
/// Number of template parameters.
static constexpr int size = sizeof...(Ts);

/// Rebinds parameter pack to a given template.
template <template <typename...> class Tpl>
using bind = Tpl<Ts...>;

/// Extracts the Ith type from this sequence.
template <size_t I>
using type_at = typename drake::type_at<I, Ts...>::type;
};

/// Returns an expression (only to be used in `decltype`) for inferring
/// and binding a parameter pack to a template.
template <template <typename...> class Tpl, typename ... Ts>
Tpl<Ts...> type_bind(type_pack<Ts...>);

/// Extracts the inner template arguments (typename only) for a typename which
/// is a template instantiation.
template <typename T>
using type_pack_extract = typename detail::type_pack_extract_impl<T>::type;

/// Visit a type by constructing its default value.
/// Useful for iterating over `type_tag`, `type_pack`, `std::integral_constant`,
/// etc.
struct type_visit_with_default {
template <typename T, typename Visitor>
inline static void run(Visitor&& visitor) {
// TODO(eric.cousineau): Figure out how to make this the only error, without
// wasting more function calls.
(void)detail::assert_default_constructible<T>{};
visitor(T{});
}
};

/// Visits a type by construct a template tag's default value.
template <template <typename> class Tag = type_tag>
struct type_visit_with_tag {
template <typename T, typename Visitor>
inline static void run(Visitor&& visitor) {
visitor(Tag<T>{});
}
};

/// Provides a check which will return true for any type.
template <typename T>
using type_check_always_true = std::true_type;

/// Provides backport of C++17 `std::negation`.
// TODO(eric.cousineau): Remove this once C++17 is used.
template <typename T>
using negation = std::integral_constant<bool, !T::value>;

/// Provides a check which returns whether `T` is different than `U`.
template <typename T>
struct type_check_different_from {
template <typename U>
using type = negation<std::is_same<T, U>>;
};

/// Visits each type in a type pack.
/// @tparam VisitWith
/// Visit helper. @see `type_visit_with_default`, `type_visit_with_tag.
/// @tparam Predicate Predicate operating on the type dictated by `VisitWith`.
/// @param visitor Lambda or functor for visiting a type.
template <class VisitWith = type_visit_with_default,
template <typename> class Predicate = type_check_always_true,
typename Visitor = void,
typename ... Ts>
void type_visit(
Visitor&& visitor, type_pack<Ts...> = {}, template_tag<Predicate> = {},
VisitWith = {}) {
(void)detail::DummyList{(
detail::type_visit_impl<VisitWith, Visitor>::
template runner<Ts, Predicate<Ts>::value>::
run(std::forward<Visitor>(visitor)),
true)...};
}

/// Transforms an integer sequence.
/// @tparam TForm
/// Type with the interface `TForm::template type<T>::value`,
/// which operates on a constexpr value.
/// @tparam T Integral type.
/// @tparam Values... Integral values.
template <typename TForm, typename T, T... Values>
auto sequence_transform(TForm = {}, std::integer_sequence<T, Values...> = {}) {
return std::integer_sequence<T, TForm::template type<Values>::value...>{};
}

/// Adds a constant value to a constexpr value.
template <typename T, T x>
struct constant_add {
template <T y>
using type = std::integral_constant<T, x + y>;
};

/// Provides short-hand for hashing a type.
template <typename T>
constexpr size_t type_hash() {
return std::type_index(typeid(T)).hash_code();
}

} // namespace drake

0 comments on commit 9a0863b

Please sign in to comment.