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

Deprecate the void shared_ptr<MessageT> subscription callback signatures #1713

Merged
merged 6 commits into from
Aug 26, 2021
Merged
Show file tree
Hide file tree
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
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")]]
aprotyas marked this conversation as resolved.
Show resolved Hide resolved
#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