Skip to content

Commit

Permalink
Deprecate the void shared_ptr<MessageT> subscription callback signa…
Browse files Browse the repository at this point in the history
…tures (#1713)

* Deprecated `shared_ptr<MessageT>` sub callbacks

Addresses #1619.

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>

* Resolve deprecated subscription callbacks in tests

Specifically, `void shared_ptr<MessageT>` subscription callbacks have
been migrated to `void shared_ptr<const MessageT>` subscription
callbacks.

This change has been performed only on the test files that do
not actually house unit tests for the `AnySubscriptionCallback` class.
For unit tests that actually target the deprecated `set` functions,
the deprecation warnings have to be avoided. This patch will be
introduced in a separate commit.

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>

* Suppress deprecation warnings in unit tests

This commit specifically introduces suppression of the deprecation
warnings produced while compiling unit tests for the
`AnySubscriptionCallback` class.

The macro mechanics to conditionally include the `deprecated` attribute
is not ideal, but the diagnostic pragma solution (`# pragma GCC
diagnostic ignored`) did not work for these unit tests, possibly because
of the way gtest is initializing the necessary `InstanceContext`
objects.

A `TODO` directive has been left to figure out a better way to address
this warning suppression.

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>

* Fix shared ptr callback in wait_for_message

Moving away from deprecated signatures.

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>

* `rclcpp_action`: Fix deprecated subscr. callbacks

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>

* `rclcpp_lifecycle`: Fix deprecated sub callbacks

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>
  • Loading branch information
Abrar Rahman Protyasha authored Aug 26, 2021
1 parent d0cd6bb commit ecb81ef
Show file tree
Hide file tree
Showing 8 changed files with 29 additions and 25 deletions.
18 changes: 10 additions & 8 deletions rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -406,10 +406,10 @@ class AnySubscriptionCallback

/// Function for shared_ptr to non-const MessageT, which is deprecated.
template<typename SetT>
// TODO(wjwwood): enable this deprecation after Galactic
// [[deprecated(
// "use 'void (std::shared_ptr<const MessageT>)' instead"
// )]]
#if !defined(RCLCPP_AVOID_DEPRECATIONS_FOR_UNIT_TESTS)
// suppress deprecation warnings in `test_any_subscription_callback.cpp`
[[deprecated("use 'void(std::shared_ptr<const MessageT>)' instead")]]
#endif
void
set_deprecated(std::function<void(std::shared_ptr<SetT>)> callback)
{
Expand All @@ -418,10 +418,12 @@ class AnySubscriptionCallback

/// Function for shared_ptr to non-const MessageT with MessageInfo, which is deprecated.
template<typename SetT>
// TODO(wjwwood): enable this deprecation after Galactic
// [[deprecated(
// "use 'void (std::shared_ptr<const MessageT>, const rclcpp::MessageInfo &)' instead"
// )]]
#if !defined(RCLCPP_AVOID_DEPRECATIONS_FOR_UNIT_TESTS)
// suppress deprecation warnings in `test_any_subscription_callback.cpp`
[[deprecated(
"use 'void(std::shared_ptr<const MessageT>, const rclcpp::MessageInfo &)' instead"
)]]
#endif
void
set_deprecated(std::function<void(std::shared_ptr<SetT>, const rclcpp::MessageInfo &)> callback)
{
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/wait_for_message.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ bool wait_for_message(
const std::string & topic,
std::chrono::duration<Rep, Period> time_to_wait = std::chrono::duration<Rep, Period>(-1))
{
auto sub = node->create_subscription<MsgT>(topic, 1, [](const std::shared_ptr<MsgT>) {});
auto sub = node->create_subscription<MsgT>(topic, 1, [](const std::shared_ptr<const MsgT>) {});
return wait_for_message<MsgT, Rep, Period>(
out, sub, node->get_node_options().context(), time_to_wait);
}
Expand Down
2 changes: 2 additions & 0 deletions rclcpp/test/rclcpp/test_any_subscription_callback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
#include <string>
#include <utility>

// TODO(aprotyas): Figure out better way to suppress deprecation warnings.
#define RCLCPP_AVOID_DEPRECATIONS_FOR_UNIT_TESTS 1
#include "rclcpp/any_subscription_callback.hpp"
#include "test_msgs/msg/empty.hpp"
#include "test_msgs/msg/empty.h"
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/test_generic_pubsub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@ TEST_F(RclcppGenericNodeFixture, generic_publisher_uses_qos)
auto publisher = node_->create_generic_publisher(topic_name, topic_type, qos);
auto subscription = node_->create_subscription<test_msgs::msg::Strings>(
topic_name, qos,
[](std::shared_ptr<test_msgs::msg::Strings>/* message */) {});
[](std::shared_ptr<const test_msgs::msg::Strings>/* message */) {});
auto connected = [publisher, subscription]() -> bool {
return publisher->get_subscription_count() && subscription->get_publisher_count();
};
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ TEST_F(

auto callback =
[message_data, &is_received](
const rclcpp::msg::String::SharedPtr msg,
const rclcpp::msg::String::ConstSharedPtr msg,
const rclcpp::MessageInfo & message_info
) -> void
{
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/test_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -510,7 +510,7 @@ INSTANTIATE_TEST_SUITE_P(
TEST_F(TestSubscription, get_network_flow_endpoints_errors) {
initialize();
const rclcpp::QoS subscription_qos(1);
auto subscription_callback = [](test_msgs::msg::Empty::SharedPtr msg) {
auto subscription_callback = [](test_msgs::msg::Empty::ConstSharedPtr msg) {
(void)msg;
};
auto subscription = node->create_subscription<test_msgs::msg::Empty>(
Expand Down
24 changes: 12 additions & 12 deletions rclcpp_action/test/test_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -485,10 +485,10 @@ TEST_F(TestServer, publish_status_accepted)
(void)as;

// Subscribe to status messages
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
std::vector<action_msgs::msg::GoalStatusArray::ConstSharedPtr> received_msgs;
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
"fibonacci/_action/status", 10,
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
[&received_msgs](action_msgs::msg::GoalStatusArray::ConstSharedPtr list)
{
received_msgs.push_back(list);
});
Expand Down Expand Up @@ -548,10 +548,10 @@ TEST_F(TestServer, publish_status_canceling)
(void)as;

// Subscribe to status messages
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
std::vector<action_msgs::msg::GoalStatusArray::ConstSharedPtr> received_msgs;
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
"fibonacci/_action/status", 10,
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
[&received_msgs](action_msgs::msg::GoalStatusArray::ConstSharedPtr list)
{
received_msgs.push_back(list);
});
Expand Down Expand Up @@ -605,10 +605,10 @@ TEST_F(TestServer, publish_status_canceled)
(void)as;

// Subscribe to status messages
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
std::vector<action_msgs::msg::GoalStatusArray::ConstSharedPtr> received_msgs;
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
"fibonacci/_action/status", 10,
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
[&received_msgs](action_msgs::msg::GoalStatusArray::ConstSharedPtr list)
{
received_msgs.push_back(list);
});
Expand Down Expand Up @@ -664,10 +664,10 @@ TEST_F(TestServer, publish_status_succeeded)
(void)as;

// Subscribe to status messages
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
std::vector<action_msgs::msg::GoalStatusArray::ConstSharedPtr> received_msgs;
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
"fibonacci/_action/status", 10,
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
[&received_msgs](action_msgs::msg::GoalStatusArray::ConstSharedPtr list)
{
received_msgs.push_back(list);
});
Expand Down Expand Up @@ -721,10 +721,10 @@ TEST_F(TestServer, publish_status_aborted)
(void)as;

// Subscribe to status messages
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
std::vector<action_msgs::msg::GoalStatusArray::ConstSharedPtr> received_msgs;
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
"fibonacci/_action/status", 10,
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
[&received_msgs](action_msgs::msg::GoalStatusArray::ConstSharedPtr list)
{
received_msgs.push_back(list);
});
Expand Down Expand Up @@ -779,9 +779,9 @@ TEST_F(TestServer, publish_feedback)

// Subscribe to feedback messages
using FeedbackT = Fibonacci::Impl::FeedbackMessage;
std::vector<FeedbackT::SharedPtr> received_msgs;
std::vector<FeedbackT::ConstSharedPtr> received_msgs;
auto subscriber = node->create_subscription<FeedbackT>(
"fibonacci/_action/feedback", 10, [&received_msgs](FeedbackT::SharedPtr msg)
"fibonacci/_action/feedback", 10, [&received_msgs](FeedbackT::ConstSharedPtr msg)
{
received_msgs.push_back(msg);
});
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_lifecycle/test/test_lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -416,7 +416,7 @@ TEST_F(TestDefaultStateMachine, bad_mood) {
TEST_F(TestDefaultStateMachine, lifecycle_subscriber) {
auto test_node = std::make_shared<MoodyLifecycleNode<GoodMood>>("testnode");

auto cb = [](const std::shared_ptr<lifecycle_msgs::msg::State> msg) {(void) msg;};
auto cb = [](const std::shared_ptr<const lifecycle_msgs::msg::State> msg) {(void) msg;};
auto lifecycle_sub =
test_node->create_subscription<lifecycle_msgs::msg::State>("~/empty", 10, cb);

Expand Down

0 comments on commit ecb81ef

Please sign in to comment.