Skip to content

Commit

Permalink
fix adapt_type<...>::as<...> syntax
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed Apr 29, 2021
1 parent c80d285 commit 70b7c17
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 11 deletions.
24 changes: 18 additions & 6 deletions rclcpp/include/rclcpp/type_adapter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,17 +116,29 @@ struct is_type_adapter<TypeAdapter<Ts...>>: std::true_type {};
template<typename T>
struct TypeAdapter<T, void, std::enable_if_t<is_type_adapter<T>::value>>: T {};

namespace detail
{

template<typename CustomType, typename ROSMessageType>
struct assert_type_pair_is_specialized_type_adapter
{
using type_adapter = TypeAdapter<CustomType, ROSMessageType>;
static_assert(
type_adapter::is_specialized::value,
"No type adapter for this custom type/ros message type pair");
};

} // detail

/// Template metafunction that can make the type being adapted explicit.
template<typename CustomType>
struct adapt_type
{
template<typename ROSMessageType>
struct as : TypeAdapter<CustomType, ROSMessageType>
{
static_assert(
TypeAdapter<CustomType, ROSMessageType>::is_specialized::value,
"No type adapter for this custom type/ros message type pair");
};
using as = typename ::rclcpp::detail::assert_type_pair_is_specialized_type_adapter<
CustomType,
ROSMessageType
>::type_adapter;
};

/// Implicit type adapter used as a short hand way to create something with just the custom type.
Expand Down
2 changes: 0 additions & 2 deletions rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,13 +156,11 @@ TEST_F(TestPublisher, various_creation_signatures) {
auto publisher = node->create_publisher<StringTypeAdapter>("topic", 42);
(void)publisher;
}
/* TODO(audrow) Enable this test once the adapt_type<>::as<> syntax is supported
{
using StringTypeAdapter = rclcpp::adapt_type<std::string>::as<rclcpp::msg::String>;
auto publisher = node->create_publisher<StringTypeAdapter>("topic", 42);
(void)publisher;
}
*/
}
}

Expand Down
5 changes: 2 additions & 3 deletions rclcpp/test/rclcpp/test_subscription_with_type_adapter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,13 +139,12 @@ TEST_F(TestSubscription, various_creation_signatures) {
node->create_subscription<StringTypeAdapter>("topic", 42, [](const std::string &) {});
(void)sub;
}
/* TODO(audrow) Enable this test once the adapt_type<>::as<> syntax is supported
{
using StringTypeAdapter = rclcpp::adapt_type<std::string>::as<rclcpp::msg::String>;
auto sub = node->create_subscription<StringTypeAdapter>("topic", 42, [](const std::string &) {});
auto sub =
node->create_subscription<StringTypeAdapter>("topic", 42, [](const std::string &) {});
(void)sub;
}
*/
}

/*
Expand Down

0 comments on commit 70b7c17

Please sign in to comment.