diff --git a/rclcpp/include/rclcpp/any_subscription_callback.hpp b/rclcpp/include/rclcpp/any_subscription_callback.hpp index bb45d6a07d..62e116af56 100644 --- a/rclcpp/include/rclcpp/any_subscription_callback.hpp +++ b/rclcpp/include/rclcpp/any_subscription_callback.hpp @@ -406,10 +406,10 @@ class AnySubscriptionCallback /// Function for shared_ptr to non-const MessageT, which is deprecated. template - // TODO(wjwwood): enable this deprecation after Galactic - // [[deprecated( - // "use 'void (std::shared_ptr)' instead" - // )]] +#if !defined(RCLCPP_AVOID_DEPRECATIONS_FOR_UNIT_TESTS) + // suppress deprecation warnings in `test_any_subscription_callback.cpp` + [[deprecated("use 'void(std::shared_ptr)' instead")]] +#endif void set_deprecated(std::function)> callback) { @@ -418,10 +418,12 @@ class AnySubscriptionCallback /// Function for shared_ptr to non-const MessageT with MessageInfo, which is deprecated. template - // TODO(wjwwood): enable this deprecation after Galactic - // [[deprecated( - // "use 'void (std::shared_ptr, 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 rclcpp::MessageInfo &)' instead" + )]] +#endif void set_deprecated(std::function, const rclcpp::MessageInfo &)> callback) { diff --git a/rclcpp/include/rclcpp/wait_for_message.hpp b/rclcpp/include/rclcpp/wait_for_message.hpp index f5f3adc9a4..20c9df4db6 100644 --- a/rclcpp/include/rclcpp/wait_for_message.hpp +++ b/rclcpp/include/rclcpp/wait_for_message.hpp @@ -90,7 +90,7 @@ bool wait_for_message( const std::string & topic, std::chrono::duration time_to_wait = std::chrono::duration(-1)) { - auto sub = node->create_subscription(topic, 1, [](const std::shared_ptr) {}); + auto sub = node->create_subscription(topic, 1, [](const std::shared_ptr) {}); return wait_for_message( out, sub, node->get_node_options().context(), time_to_wait); } diff --git a/rclcpp/test/rclcpp/test_any_subscription_callback.cpp b/rclcpp/test/rclcpp/test_any_subscription_callback.cpp index 8e44eb71bf..32abdf2934 100644 --- a/rclcpp/test/rclcpp/test_any_subscription_callback.cpp +++ b/rclcpp/test/rclcpp/test_any_subscription_callback.cpp @@ -19,6 +19,8 @@ #include #include +// 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" diff --git a/rclcpp/test/rclcpp/test_generic_pubsub.cpp b/rclcpp/test/rclcpp/test_generic_pubsub.cpp index 71a60a77fb..ff34ec52b3 100644 --- a/rclcpp/test/rclcpp/test_generic_pubsub.cpp +++ b/rclcpp/test/rclcpp/test_generic_pubsub.cpp @@ -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( topic_name, qos, - [](std::shared_ptr/* message */) {}); + [](std::shared_ptr/* message */) {}); auto connected = [publisher, subscription]() -> bool { return publisher->get_subscription_count() && subscription->get_publisher_count(); }; diff --git a/rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp b/rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp index 2f5d540568..f5ab43cb7c 100644 --- a/rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp +++ b/rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp @@ -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 { diff --git a/rclcpp/test/rclcpp/test_subscription.cpp b/rclcpp/test/rclcpp/test_subscription.cpp index 2895865c1f..5812985272 100644 --- a/rclcpp/test/rclcpp/test_subscription.cpp +++ b/rclcpp/test/rclcpp/test_subscription.cpp @@ -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( diff --git a/rclcpp_action/test/test_server.cpp b/rclcpp_action/test/test_server.cpp index 6f8d874359..7030243c77 100644 --- a/rclcpp_action/test/test_server.cpp +++ b/rclcpp_action/test/test_server.cpp @@ -485,10 +485,10 @@ TEST_F(TestServer, publish_status_accepted) (void)as; // Subscribe to status messages - std::vector received_msgs; + std::vector received_msgs; auto subscriber = node->create_subscription( "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); }); @@ -548,10 +548,10 @@ TEST_F(TestServer, publish_status_canceling) (void)as; // Subscribe to status messages - std::vector received_msgs; + std::vector received_msgs; auto subscriber = node->create_subscription( "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); }); @@ -605,10 +605,10 @@ TEST_F(TestServer, publish_status_canceled) (void)as; // Subscribe to status messages - std::vector received_msgs; + std::vector received_msgs; auto subscriber = node->create_subscription( "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); }); @@ -664,10 +664,10 @@ TEST_F(TestServer, publish_status_succeeded) (void)as; // Subscribe to status messages - std::vector received_msgs; + std::vector received_msgs; auto subscriber = node->create_subscription( "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); }); @@ -721,10 +721,10 @@ TEST_F(TestServer, publish_status_aborted) (void)as; // Subscribe to status messages - std::vector received_msgs; + std::vector received_msgs; auto subscriber = node->create_subscription( "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); }); @@ -779,9 +779,9 @@ TEST_F(TestServer, publish_feedback) // Subscribe to feedback messages using FeedbackT = Fibonacci::Impl::FeedbackMessage; - std::vector received_msgs; + std::vector received_msgs; auto subscriber = node->create_subscription( - "fibonacci/_action/feedback", 10, [&received_msgs](FeedbackT::SharedPtr msg) + "fibonacci/_action/feedback", 10, [&received_msgs](FeedbackT::ConstSharedPtr msg) { received_msgs.push_back(msg); }); diff --git a/rclcpp_lifecycle/test/test_lifecycle_node.cpp b/rclcpp_lifecycle/test/test_lifecycle_node.cpp index 7ee883a5f0..e1863a4d39 100644 --- a/rclcpp_lifecycle/test/test_lifecycle_node.cpp +++ b/rclcpp_lifecycle/test/test_lifecycle_node.cpp @@ -416,7 +416,7 @@ TEST_F(TestDefaultStateMachine, bad_mood) { TEST_F(TestDefaultStateMachine, lifecycle_subscriber) { auto test_node = std::make_shared>("testnode"); - auto cb = [](const std::shared_ptr msg) {(void) msg;}; + auto cb = [](const std::shared_ptr msg) {(void) msg;}; auto lifecycle_sub = test_node->create_subscription("~/empty", 10, cb);