Skip to content

Commit

Permalink
deprecated callback_group from publisher option
Browse files Browse the repository at this point in the history
Signed-off-by: Chen Lihui <lihui.chen@sony.com>
  • Loading branch information
Chen Lihui committed Jan 4, 2022
1 parent 7a2ee23 commit e89dd70
Show file tree
Hide file tree
Showing 8 changed files with 89 additions and 24 deletions.
25 changes: 22 additions & 3 deletions rclcpp/include/rclcpp/create_generic_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ namespace rclcpp
* \param qos %QoS settings
* \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`.
* publisher are `event_callbacks` and `use_default_callbacks`.
* \param group Callback group to execute this publisher's callback(e.g. QoS Events).
*/
template<typename AllocatorT = std::allocator<void>>
std::shared_ptr<GenericPublisher> create_generic_publisher(
Expand All @@ -49,7 +50,8 @@ std::shared_ptr<GenericPublisher> create_generic_publisher(
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
)
),
rclcpp::CallbackGroup::SharedPtr group = nullptr
)
{
auto ts_lib = rclcpp::get_typesupport_library(topic_type, "rosidl_typesupport_cpp");
Expand All @@ -60,7 +62,24 @@ std::shared_ptr<GenericPublisher> create_generic_publisher(
topic_type,
qos,
options);
topics_interface->add_publisher(pub, 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 (group == nullptr) {
group = options.callback_group;
}
#ifndef _WIN32
# pragma GCC diagnostic pop
#else
# pragma warning(pop)
#endif

topics_interface->add_publisher(pub, group);
return pub;
}

Expand Down
30 changes: 24 additions & 6 deletions rclcpp/include/rclcpp/create_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,8 @@ create_publisher(
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
)
),
rclcpp::CallbackGroup::SharedPtr group = nullptr
)
{
auto node_topics_interface = rclcpp::node_interfaces::get_node_topics_interface(node_topics);
Expand All @@ -68,8 +69,23 @@ create_publisher(
actual_qos
);

#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
if (group == nullptr) {
group = options.callback_group;
}
#ifndef _WIN32
# pragma GCC diagnostic pop
#else
# pragma warning(pop)
#endif
// Add the publisher to the node topics interface.
node_topics_interface->add_publisher(pub, options.callback_group);
node_topics_interface->add_publisher(pub, group);

return std::dynamic_pointer_cast<PublisherT>(pub);
}
Expand Down Expand Up @@ -97,11 +113,12 @@ create_publisher(
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
)
),
rclcpp::CallbackGroup::SharedPtr group = nullptr
)
{
return detail::create_publisher<MessageT, AllocatorT, PublisherT>(
node, node, topic_name, qos, options);
node, node, topic_name, qos, options, group);
}

/// Create and return a publisher of the given MessageT type.
Expand All @@ -117,11 +134,12 @@ create_publisher(
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
)
),
rclcpp::CallbackGroup::SharedPtr group = nullptr
)
{
return detail::create_publisher<MessageT, AllocatorT, PublisherT>(
node_parameters, node_topics, topic_name, qos, options);
node_parameters, node_topics, topic_name, qos, options, group);
}

} // namespace rclcpp
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/generic_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class GenericPublisher : public rclcpp::PublisherBase
* \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`.
* publisher are `event_callbacks` and `use_default_callbacks`.
*/
template<typename AllocatorT = std::allocator<void>>
GenericPublisher(
Expand Down
12 changes: 8 additions & 4 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,7 @@ class Node : public std::enable_shared_from_this<Node>
* \param[in] topic_name The topic for this publisher to publish on.
* \param[in] qos The Quality of Service settings for the publisher.
* \param[in] options Additional options for the created Publisher.
* \param[in] group Callback group to execute this publisher's callback(e.g. QoS Events).
* \return Shared pointer to the created publisher.
*/
template<
Expand All @@ -196,7 +197,8 @@ class Node : public std::enable_shared_from_this<Node>
const std::string & topic_name,
const rclcpp::QoS & qos,
const PublisherOptionsWithAllocator<AllocatorT> & options =
PublisherOptionsWithAllocator<AllocatorT>()
PublisherOptionsWithAllocator<AllocatorT>(),
rclcpp::CallbackGroup::SharedPtr group = nullptr
);

/// Create and return a Subscription.
Expand Down Expand Up @@ -278,9 +280,10 @@ class Node : public std::enable_shared_from_this<Node>
* \param[in] topic_name Topic name
* \param[in] topic_type Topic type
* \param[in] qos %QoS settings
* \param options %Publisher options.
* \param[in] options %Publisher options.
* \param[in] group %Publisher group.
* Not all publisher options are currently respected, the only relevant options for this
* publisher are `event_callbacks`, `use_default_callbacks`, and `%callback_group`.
* publisher are `event_callbacks` and `use_default_callbacks`.
* \return Shared pointer to the created generic publisher.
*/
template<typename AllocatorT = std::allocator<void>>
Expand All @@ -290,7 +293,8 @@ class Node : public std::enable_shared_from_this<Node>
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
)
),
rclcpp::CallbackGroup::SharedPtr group = nullptr
);

/// Create and return a GenericSubscription.
Expand Down
12 changes: 8 additions & 4 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,13 +73,15 @@ std::shared_ptr<PublisherT>
Node::create_publisher(
const std::string & topic_name,
const rclcpp::QoS & qos,
const PublisherOptionsWithAllocator<AllocatorT> & options)
const PublisherOptionsWithAllocator<AllocatorT> & options,
rclcpp::CallbackGroup::SharedPtr group)
{
return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
*this,
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
qos,
options);
options,
group);
}

template<
Expand Down Expand Up @@ -159,14 +161,16 @@ Node::create_generic_publisher(
const std::string & topic_name,
const std::string & topic_type,
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options)
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options,
rclcpp::CallbackGroup::SharedPtr group)
{
return rclcpp::create_generic_publisher(
node_topics_,
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
topic_type,
qos,
options
options,
group
);
}

Expand Down
13 changes: 13 additions & 0 deletions rclcpp/include/rclcpp/publisher_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,13 @@ namespace rclcpp

class CallbackGroup;

#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
/// Non-templated part of PublisherOptionsWithAllocator<Allocator>.
struct PublisherOptionsBase
{
Expand All @@ -52,6 +59,7 @@ struct PublisherOptionsBase
RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_NOT_REQUIRED;

/// Callback group in which the waitable items from the publisher should be placed.
[[deprecated("use create_publisher with a dedicated callback_group instead")]]
std::shared_ptr<rclcpp::CallbackGroup> callback_group;

/// Optional RMW implementation specific payload to be used during creation of the publisher.
Expand All @@ -60,6 +68,11 @@ struct PublisherOptionsBase

QosOverridingOptions qos_overriding_options;
};
#ifndef _WIN32
# pragma GCC diagnostic pop
#else
# pragma warning(pop)
#endif

/// Structure containing optional configuration for Publishers.
template<typename Allocator>
Expand Down
7 changes: 5 additions & 2 deletions rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -203,6 +203,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
* \param[in] topic_name The topic for this publisher to publish on.
* \param[in] qos The Quality of Service settings for this publisher.
* \param[in] options The publisher options for this publisher.
* \param[in] group Callback group to execute this publisher's callback(e.g. QoS Events).
* \return Shared pointer to the created lifecycle publisher.
*/
template<typename MessageT, typename AllocatorT = std::allocator<void>>
Expand All @@ -212,7 +213,8 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
const rclcpp::QoS & qos,
const PublisherOptionsWithAllocator<AllocatorT> & options = (
create_default_publisher_options<AllocatorT>()
)
),
rclcpp::CallbackGroup::SharedPtr group = nullptr
);

/// Create and return a Subscription.
Expand Down Expand Up @@ -289,7 +291,8 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
)
),
rclcpp::CallbackGroup::SharedPtr group = nullptr
);

/// Create and return a GenericSubscription.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,14 +46,16 @@ std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, AllocatorT>>
LifecycleNode::create_publisher(
const std::string & topic_name,
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options)
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options,
rclcpp::CallbackGroup::SharedPtr group)
{
using PublisherT = rclcpp_lifecycle::LifecyclePublisher<MessageT, AllocatorT>;
return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
*this,
topic_name,
qos,
options);
options,
group);
}

// TODO(karsten1987): Create LifecycleSubscriber
Expand Down Expand Up @@ -137,7 +139,8 @@ LifecycleNode::create_generic_publisher(
const std::string & topic_name,
const std::string & topic_type,
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options)
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options,
rclcpp::CallbackGroup::SharedPtr group)
{
return rclcpp::create_generic_publisher(
node_topics_,
Expand All @@ -146,7 +149,8 @@ LifecycleNode::create_generic_publisher(
topic_name,
topic_type,
qos,
options
options,
group
);
}

Expand Down

0 comments on commit e89dd70

Please sign in to comment.