Merge pull request #131 from ros2/callback-unique-ptr

Unify create_subscription API
This commit is contained in:
Esteve Fernandez 2015-10-15 14:35:40 -07:00
commit 1d5720f964
3 changed files with 52 additions and 123 deletions

View file

@ -114,35 +114,28 @@ struct AnySubscriptionCallback
{ {
const_shared_ptr_with_info_callback = callback; const_shared_ptr_with_info_callback = callback;
} }
/*
template<typename CallbackT, template<
typename CallbackT,
typename std::enable_if< typename std::enable_if<
function_traits<CallbackT>::arity == 1 rclcpp::check_argument_types<
>::type * = nullptr, CallbackT,
typename std::enable_if<
std::is_same<
typename function_traits<CallbackT>::template argument_type<0>,
typename std::unique_ptr<MessageT> typename std::unique_ptr<MessageT>
>::value >::value
>::type * = nullptr >::type * = nullptr
> >
void set(CallbackT callback) 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; unique_ptr_callback = callback;
} }
template<typename CallbackT, template<
typename CallbackT,
typename std::enable_if< typename std::enable_if<
function_traits<CallbackT>::arity == 2 rclcpp::check_argument_types<
>::type * = nullptr, CallbackT,
typename std::enable_if< typename std::unique_ptr<MessageT>,
std::is_same< const rmw_message_info_t &
typename function_traits<CallbackT>::template argument_type<0>,
typename std::unique_ptr<MessageT>
>::value >::value
>::type * = nullptr >::type * = nullptr
> >
@ -150,7 +143,6 @@ struct AnySubscriptionCallback
{ {
unique_ptr_with_info_callback = callback; unique_ptr_with_info_callback = callback;
} }
*/
}; };
} /* namespace any_subscription_callback */ } /* namespace any_subscription_callback */

View file

@ -114,31 +114,6 @@ public:
create_publisher( create_publisher(
const std::string & topic_name, const rmw_qos_profile_t & qos_profile); const std::string & topic_name, const rmw_qos_profile_t & qos_profile);
/// 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] 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.
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
* \return Shared pointer to the created subscription.
*/
/* TODO(jacquelinekay):
Windows build breaks when static member function passed as default
argument to msg_mem_strat, nullptr is a workaround.
*/
template<typename MessageT, typename CallbackT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
create_subscription(
const std::string & topic_name,
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);
/// Create and return a Subscription. /// Create and return a Subscription.
/** /**
* \param[in] topic_name The topic to subscribe on. * \param[in] topic_name The topic to subscribe on.
@ -164,12 +139,26 @@ public:
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
msg_mem_strat = nullptr); msg_mem_strat = nullptr);
template<typename MessageT> /// 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] 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.
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
* \return Shared pointer to the created subscription.
*/
/* TODO(jacquelinekay):
Windows build breaks when static member function passed as default
argument to msg_mem_strat, nullptr is a workaround.
*/
template<typename MessageT, typename CallbackT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
create_subscription_with_unique_ptr_callback( create_subscription(
const std::string & topic_name, const std::string & topic_name,
const rmw_qos_profile_t & qos_profile, size_t qos_history_depth,
typename rclcpp::subscription::AnySubscriptionCallback<MessageT>::UniquePtrCallback callback, CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr, rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
bool ignore_local_publications = false, bool ignore_local_publications = false,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
@ -273,16 +262,6 @@ private:
publisher::Publisher<rcl_interfaces::msg::ParameterEvent>::SharedPtr events_publisher_; 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< template<
typename ServiceT, typename ServiceT,
typename FunctorT, typename FunctorT,

View file

@ -205,30 +205,6 @@ Node::group_in_node(callback_group::CallbackGroup::SharedPtr group)
return group_belongs_to_this_node; 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> template<typename MessageT, typename CallbackT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
Node::create_subscription( Node::create_subscription(
@ -242,47 +218,7 @@ Node::create_subscription(
{ {
rclcpp::subscription::AnySubscriptionCallback<MessageT> any_subscription_callback; rclcpp::subscription::AnySubscriptionCallback<MessageT> any_subscription_callback;
any_subscription_callback.set(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; using rosidl_generator_cpp::get_message_type_support_handle;
if (!msg_mem_strat) { if (!msg_mem_strat) {
@ -308,7 +244,7 @@ Node::create_subscription_internal(
subscriber_handle, subscriber_handle,
topic_name, topic_name,
ignore_local_publications, ignore_local_publications,
callback, any_subscription_callback,
msg_mem_strat); msg_mem_strat);
auto sub_base_ptr = std::dynamic_pointer_cast<SubscriptionBase>(sub); auto sub_base_ptr = std::dynamic_pointer_cast<SubscriptionBase>(sub);
// Setup intra process. // Setup intra process.
@ -370,6 +306,28 @@ Node::create_subscription_internal(
return sub; 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 rclcpp::timer::WallTimer::SharedPtr
Node::create_wall_timer( Node::create_wall_timer(
std::chrono::nanoseconds period, std::chrono::nanoseconds period,