Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

not to hold callback group in subscription #1833

Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 23 additions & 5 deletions rclcpp/include/rclcpp/create_generic_subscription.hpp
Original file line number Diff line number Diff line change
@@ -41,9 +41,10 @@ namespace rclcpp
* \param topic_type Topic type
* \param qos %QoS settings
* \param callback Callback for new messages of serialized form
* \param options %Publisher options.
* Not all publisher options are currently respected, the only relevant options for this
* publisher are `event_callbacks`, `use_default_callbacks`, and `%callback_group`.
* \param options %Subscription options.
* Not all subscription options are currently respected, the only relevant options for this
* subscription are `event_callbacks` and `use_default_callbacks`.
* \param callback_group Callback group to execute this subscription's callback.
*/
template<typename AllocatorT = std::allocator<void>>
std::shared_ptr<GenericSubscription> create_generic_subscription(
@@ -54,7 +55,8 @@ std::shared_ptr<GenericSubscription> create_generic_subscription(
std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)> callback,
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
)
),
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr
)
{
auto ts_lib = rclcpp::get_typesupport_library(
@@ -69,7 +71,23 @@ std::shared_ptr<GenericSubscription> create_generic_subscription(
callback,
options);

topics_interface->add_subscription(subscription, options.callback_group);
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
if (callback_group == nullptr) {
callback_group = options.callback_group;
}
#ifndef _WIN32
# pragma GCC diagnostic pop
#else
# pragma warning(pop)
#endif

topics_interface->add_subscription(subscription, callback_group);

return subscription;
}
107 changes: 103 additions & 4 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
@@ -62,6 +62,7 @@ create_subscription(
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
),
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr,
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
MessageMemoryStrategyT::create_default()
)
@@ -111,7 +112,7 @@ create_subscription(
std::chrono::duration_cast<std::chrono::nanoseconds>(
options.topic_stats_options.publish_period),
sub_call_back,
options.callback_group,
callback_group,
node_topics_interface->get_node_base_interface(),
node_timer_interface
);
@@ -134,7 +135,24 @@ create_subscription(
qos;

auto sub = node_topics_interface->create_subscription(topic_name, factory, actual_qos);
node_topics_interface->add_subscription(sub, options.callback_group);

#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
if (callback_group == nullptr) {
callback_group = options.callback_group;
}
#ifndef _WIN32
# pragma GCC diagnostic pop
#else
# pragma warning(pop)
#endif

node_topics_interface->add_subscription(sub, callback_group);

return std::dynamic_pointer_cast<SubscriptionT>(sub);
}
@@ -173,6 +191,57 @@ template<
typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType,
typename NodeT>
[[deprecated("use another overloaded method create_subscription instead")]]
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we should mention that the purpose of the deprecation is to have a separate argument for the callback group

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think the message in the deprecated can be either the reason or suggestion, what about adding the reason here?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'll follow your suggestion, what about

Suggested change
[[deprecated("use another overloaded method create_subscription instead")]]
[[deprecated(
"To Keep consistency with other cases(Client, Service, Timer, etc) not hold callback_group,\n" \
"the callback_group in the SubscriptionOptionsBase will be removed in the future since the\n" \
"SubscriptionOptions is held in the Subscription and then the callback_group is depend\n" \
"on the lifetime of Subscription.\n" \
"Use\n" \
" template<\n" \
" typename MessageT,\n" \
" typename CallbackT,\n" \
" typename AllocatorT = std::allocator<void>,\n" \
" typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,\n" \
" typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType\n" \
" typename NodeT>\n" \
" typename std::shared_ptr<SubscriptionT>\n" \
" create_subscription(\n" \
" NodeT & node,\n" \
" const std::string & topic_name,\n" \
" const rclcpp::QoS & qos,\n" \
" CallbackT && callback,\n" \
" const SubscriptionOptionsWithAllocator<AllocatorT> & options =(\n" \
" SubscriptionOptionsWithAllocator<AllocatorT>()\n" \
" ),\n" \
" rclcpp::CallbackGroup::SharedPtr group = nullptr,\n" \
" typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (\n" \
" MessageMemoryStrategyT::create_default()\n" \
" )\n" \
" );\n" \
"instead"
)]]

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

i think suggestion would be okay enough, since reason can be found on git history and on this issue.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actually, I agree that the deprecation message should be more specific. While some one could figure out why this change is happening by looking at the git/github history, that's not reasonable for the average user.

On the other hand I think the suggestion above is a bit too verbose.

I would propose something like:

Suggested change
[[deprecated("use another overloaded method create_subscription instead")]]
[[deprecated(
"use the signature which has the callback group before the message memory strategy, i.e. "
"create_subscription(node, topic_name, qos, callback, options, callback_group, msg_mem_strat)"
)]]

I believe this suggestion is still under the line limit, but check the linters if you take it more or less as-is.

typename std::shared_ptr<SubscriptionT>
create_subscription(
NodeT & node,
const std::string & topic_name,
const rclcpp::QoS & qos,
CallbackT && callback,
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat
)
{
return rclcpp::detail::create_subscription<
MessageT, CallbackT, AllocatorT, SubscriptionT, MessageMemoryStrategyT>(
node, node, topic_name, qos, std::forward<CallbackT>(callback), options,
options.callback_group, msg_mem_strat);
}

/// Create and return a subscription of the given MessageT type.
/**
* The NodeT type only needs to have a method called get_node_topics_interface()
* which returns a shared_ptr to a NodeTopicsInterface, or be a
* NodeTopicsInterface pointer itself.
*
* In case `options.qos_overriding_options` is enabling qos parameter overrides,
* NodeT must also have a method called get_node_parameters_interface()
* which returns a shared_ptr to a NodeParametersInterface.
*
* \tparam MessageT
* \tparam CallbackT
* \tparam AllocatorT
* \tparam SubscriptionT
* \tparam MessageMemoryStrategyT
* \tparam NodeT
* \param node
* \param topic_name
* \param qos
* \param callback
* \param options
* \param callback_group
* \param msg_mem_strat
* \return the created subscription
* \throws std::invalid_argument if topic statistics is enabled and the publish period is
* less than or equal to zero.
*/
template<
typename MessageT,
typename CallbackT,
typename AllocatorT = std::allocator<void>,
typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType,
typename NodeT>
typename std::shared_ptr<SubscriptionT>
create_subscription(
NodeT & node,
@@ -182,14 +251,43 @@ create_subscription(
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
),
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr,
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
MessageMemoryStrategyT::create_default()
)
)
{
return rclcpp::detail::create_subscription<
MessageT, CallbackT, AllocatorT, SubscriptionT, MessageMemoryStrategyT>(
node, node, topic_name, qos, std::forward<CallbackT>(callback), options, msg_mem_strat);
node, node, topic_name, qos, std::forward<CallbackT>(callback), options, callback_group,
msg_mem_strat);
}

/// Create and return a subscription of the given MessageT type.
/**
* See \ref create_subscription().
*/
template<
typename MessageT,
typename CallbackT,
typename AllocatorT = std::allocator<void>,
typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType>
typename std::shared_ptr<SubscriptionT>
create_subscription(
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters,
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr & node_topics,
const std::string & topic_name,
const rclcpp::QoS & qos,
CallbackT && callback,
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat
)
{
return rclcpp::detail::create_subscription<
MessageT, CallbackT, AllocatorT, SubscriptionT, MessageMemoryStrategyT>(
node_parameters, node_topics, topic_name, qos,
std::forward<CallbackT>(callback), options, options.callback_group, msg_mem_strat);
}

/// Create and return a subscription of the given MessageT type.
@@ -212,6 +310,7 @@ create_subscription(
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
),
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr,
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
MessageMemoryStrategyT::create_default()
)
@@ -220,7 +319,7 @@ create_subscription(
return rclcpp::detail::create_subscription<
MessageT, CallbackT, AllocatorT, SubscriptionT, MessageMemoryStrategyT>(
node_parameters, node_topics, topic_name, qos,
std::forward<CallbackT>(callback), options, msg_mem_strat);
std::forward<CallbackT>(callback), options, callback_group, msg_mem_strat);
}

} // namespace rclcpp
3 changes: 1 addition & 2 deletions rclcpp/include/rclcpp/generic_subscription.hpp
Original file line number Diff line number Diff line change
@@ -64,8 +64,7 @@ class GenericSubscription : public rclcpp::SubscriptionBase
* \param callback Callback for new messages of serialized form
* \param options %Subscription options.
* Not all subscription options are currently respected, the only relevant options for this
* subscription are `event_callbacks`, `use_default_callbacks`, `ignore_local_publications`, and
* `%callback_group`.
* subscription are `event_callbacks`, `use_default_callbacks` and `ignore_local_publications`.
*/
template<typename AllocatorT = std::allocator<void>>
GenericSubscription(
35 changes: 32 additions & 3 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
@@ -215,13 +215,41 @@ class Node : public std::enable_shared_from_this<Node>
typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType
>
[[deprecated("use another overloaded method create_subscription instead")]]
std::shared_ptr<SubscriptionT>
create_subscription(
const std::string & topic_name,
const rclcpp::QoS & qos,
CallbackT && callback,
const SubscriptionOptionsWithAllocator<AllocatorT> & options,
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat
);

/// Create and return a Subscription.
/**
* \param[in] topic_name The topic to subscribe on.
* \param[in] qos QoS profile for Subcription.
* \param[in] callback The user-defined callback function to receive a message
* \param[in] options Additional options for the creation of the Subscription.
* \param[in] callback_group Callback group to execute this subscription's callback.
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
* \return Shared pointer to the created subscription.
*/
template<
typename MessageT,
typename CallbackT,
typename AllocatorT = std::allocator<void>,
typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType
>
std::shared_ptr<SubscriptionT>
create_subscription(
const std::string & topic_name,
const rclcpp::QoS & qos,
CallbackT && callback,
const SubscriptionOptionsWithAllocator<AllocatorT> & options =
SubscriptionOptionsWithAllocator<AllocatorT>(),
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr,
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
MessageMemoryStrategyT::create_default()
)
@@ -304,8 +332,8 @@ class Node : public std::enable_shared_from_this<Node>
* \param[in] callback Callback for new messages of serialized form
* \param[in] options %Subscription options.
* Not all subscription options are currently respected, the only relevant options for this
* subscription are `event_callbacks`, `use_default_callbacks`, `ignore_local_publications`, and
* `%callback_group`.
* subscription are `event_callbacks`, `use_default_callbacks` and `ignore_local_publications`.
* \param[in] callback_group Callback group to execute this subscription's callback.
* \return Shared pointer to the created generic subscription.
*/
template<typename AllocatorT = std::allocator<void>>
@@ -316,7 +344,8 @@ class Node : public std::enable_shared_from_this<Node>
std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)> callback,
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
)
),
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr
);

/// Declare and initialize a parameter, return the effective value.
32 changes: 30 additions & 2 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
@@ -102,6 +102,32 @@ Node::create_subscription(
qos,
std::forward<CallbackT>(callback),
options,
options.callback_group,
msg_mem_strat);
}

template<
typename MessageT,
typename CallbackT,
typename AllocatorT,
typename SubscriptionT,
typename MessageMemoryStrategyT>
std::shared_ptr<SubscriptionT>
Node::create_subscription(
const std::string & topic_name,
const rclcpp::QoS & qos,
CallbackT && callback,
const SubscriptionOptionsWithAllocator<AllocatorT> & options,
rclcpp::CallbackGroup::SharedPtr callback_group,
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
{
return rclcpp::create_subscription<MessageT>(
*this,
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
qos,
std::forward<CallbackT>(callback),
options,
callback_group,
msg_mem_strat);
}

@@ -177,15 +203,17 @@ Node::create_generic_subscription(
const std::string & topic_type,
const rclcpp::QoS & qos,
std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)> callback,
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options)
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
rclcpp::CallbackGroup::SharedPtr callback_group)
{
return rclcpp::create_generic_subscription(
node_topics_,
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
topic_type,
qos,
std::move(callback),
options
options,
callback_group
);
}

12 changes: 8 additions & 4 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
@@ -213,13 +213,15 @@ class AsyncParametersClient
),
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
))
),
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)
{
return this->on_parameter_event(
this->node_topics_interface_,
callback,
qos,
options);
options,
callback_group);
}

/**
@@ -240,14 +242,16 @@ class AsyncParametersClient
),
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
))
),
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)
{
return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
node,
"/parameter_events",
qos,
std::forward<CallbackT>(callback),
options);
options,
callback_group);
}

/// Return if the parameter services are ready.
Loading