Skip to content

Commit

Permalink
Merge pull request #131 from ros2/callback-unique-ptr
Browse files Browse the repository at this point in the history
Unify create_subscription API
  • Loading branch information
esteve committed Oct 15, 2015
2 parents e2ade1f + 3061ec0 commit 1d5720f
Show file tree
Hide file tree
Showing 3 changed files with 38 additions and 109 deletions.
30 changes: 11 additions & 19 deletions rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,43 +114,35 @@ struct AnySubscriptionCallback
{
const_shared_ptr_with_info_callback = callback;
}
/*
template<typename CallbackT,
typename std::enable_if<
function_traits<CallbackT>::arity == 1
>::type * = nullptr,

template<
typename CallbackT,
typename std::enable_if<
std::is_same<
typename function_traits<CallbackT>::template argument_type<0>,
rclcpp::check_argument_types<
CallbackT,
typename std::unique_ptr<MessageT>
>::value
>::type * = nullptr
>
void set(CallbackT callback)
{
static_assert(std::is_same<
typename function_traits<CallbackT>::template argument_type<0>,
typename std::unique_ptr<MessageT>
>::value, "Not a unique pointer");
unique_ptr_callback = callback;
}

template<typename CallbackT,
typename std::enable_if<
function_traits<CallbackT>::arity == 2
>::type * = nullptr,
template<
typename CallbackT,
typename std::enable_if<
std::is_same<
typename function_traits<CallbackT>::template argument_type<0>,
typename std::unique_ptr<MessageT>
rclcpp::check_argument_types<
CallbackT,
typename std::unique_ptr<MessageT>,
const rmw_message_info_t &
>::value
>::type * = nullptr
>
void set(CallbackT callback)
{
unique_ptr_with_info_callback = callback;
}
*/
};

} /* namespace any_subscription_callback */
Expand Down
29 changes: 4 additions & 25 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ class Node
/// Create and return a Subscription.
/**
* \param[in] topic_name The topic to subscribe on.
* \param[in] qos_history_depth The depth of the subscription's incoming message queue.
* \param[in] qos_profile The quality of service profile to pass on to the rmw implementation.
* \param[in] callback The user-defined callback function.
* \param[in] group The callback group for this subscription. NULL for no callback group.
* \param[in] ignore_local_publications True to ignore local publications.
Expand All @@ -132,7 +132,7 @@ class Node
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
create_subscription(
const std::string & topic_name,
size_t qos_history_depth,
const rmw_qos_profile_t & qos_profile,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
bool ignore_local_publications = false,
Expand All @@ -142,7 +142,7 @@ class Node
/// Create and return a Subscription.
/**
* \param[in] topic_name The topic to subscribe on.
* \param[in] qos_profile The quality of service profile to pass on to the rmw implementation.
* \param[in] qos_history_depth The depth of the subscription's incoming message queue.
* \param[in] callback The user-defined callback function.
* \param[in] group The callback group for this subscription. NULL for no callback group.
* \param[in] ignore_local_publications True to ignore local publications.
Expand All @@ -157,24 +157,13 @@ class Node
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
create_subscription(
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile,
size_t qos_history_depth,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
bool ignore_local_publications = false,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
msg_mem_strat = nullptr);

template<typename MessageT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
create_subscription_with_unique_ptr_callback(
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile,
typename rclcpp::subscription::AnySubscriptionCallback<MessageT>::UniquePtrCallback callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
bool ignore_local_publications = false,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
msg_mem_strat = nullptr);

/// Create a timer.
/**
* \param[in] period Time interval between triggers of the callback.
Expand Down Expand Up @@ -273,16 +262,6 @@ class Node

publisher::Publisher<rcl_interfaces::msg::ParameterEvent>::SharedPtr events_publisher_;

template<typename MessageT>
typename subscription::Subscription<MessageT>::SharedPtr
create_subscription_internal(
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile,
rclcpp::subscription::AnySubscriptionCallback<MessageT> callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool ignore_local_publications,
typename message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr msg_mem_strat);

template<
typename ServiceT,
typename FunctorT,
Expand Down
88 changes: 23 additions & 65 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,30 +205,6 @@ Node::group_in_node(callback_group::CallbackGroup::SharedPtr group)
return group_belongs_to_this_node;
}

template<typename MessageT, typename CallbackT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
Node::create_subscription(
const std::string & topic_name,
size_t qos_history_depth,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool ignore_local_publications,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
msg_mem_strat)
{
rclcpp::subscription::AnySubscriptionCallback<MessageT> any_subscription_callback;
any_subscription_callback.set(callback);
rmw_qos_profile_t qos = rmw_qos_profile_default;
qos.depth = qos_history_depth;
return this->create_subscription_internal(
topic_name,
qos,
any_subscription_callback,
group,
ignore_local_publications,
msg_mem_strat);
}

template<typename MessageT, typename CallbackT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
Node::create_subscription(
Expand All @@ -242,47 +218,7 @@ Node::create_subscription(
{
rclcpp::subscription::AnySubscriptionCallback<MessageT> any_subscription_callback;
any_subscription_callback.set(callback);
return this->create_subscription_internal(
topic_name,
qos_profile,
any_subscription_callback,
group,
ignore_local_publications,
msg_mem_strat);
}

template<typename MessageT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
Node::create_subscription_with_unique_ptr_callback(
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile,
typename rclcpp::subscription::AnySubscriptionCallback<MessageT>::UniquePtrCallback callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool ignore_local_publications,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
msg_mem_strat)
{
rclcpp::subscription::AnySubscriptionCallback<MessageT> any_subscription_callback;
any_subscription_callback.unique_ptr_callback = callback;
return this->create_subscription_internal(
topic_name,
qos_profile,
any_subscription_callback,
group,
ignore_local_publications,
msg_mem_strat);
}

template<typename MessageT>
typename subscription::Subscription<MessageT>::SharedPtr
Node::create_subscription_internal(
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile,
rclcpp::subscription::AnySubscriptionCallback<MessageT> callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool ignore_local_publications,
typename message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr msg_mem_strat)
{
using rosidl_generator_cpp::get_message_type_support_handle;

if (!msg_mem_strat) {
Expand All @@ -308,7 +244,7 @@ Node::create_subscription_internal(
subscriber_handle,
topic_name,
ignore_local_publications,
callback,
any_subscription_callback,
msg_mem_strat);
auto sub_base_ptr = std::dynamic_pointer_cast<SubscriptionBase>(sub);
// Setup intra process.
Expand Down Expand Up @@ -370,6 +306,28 @@ Node::create_subscription_internal(
return sub;
}

template<typename MessageT, typename CallbackT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
Node::create_subscription(
const std::string & topic_name,
size_t qos_history_depth,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool ignore_local_publications,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
msg_mem_strat)
{
rmw_qos_profile_t qos = rmw_qos_profile_default;
qos.depth = qos_history_depth;
return this->create_subscription<MessageT, CallbackT>(
topic_name,
qos,
callback,
group,
ignore_local_publications,
msg_mem_strat);
}

rclcpp::timer::WallTimer::SharedPtr
Node::create_wall_timer(
std::chrono::nanoseconds period,
Expand Down

0 comments on commit 1d5720f

Please sign in to comment.