From 86b08b9ffbc8391ad10c73e9d81f1fbd13e65707 Mon Sep 17 00:00:00 2001 From: Abrar Rahman Protyasha Date: Thu, 19 Aug 2021 23:55:51 -0400 Subject: [PATCH] Fix deprecated subscriber callbacks These fixes target the following packages within examples: * `examples_rclcpp_cbg_executor` * `multithreaded_executor` * `minimal_subscriber` * `minimal_publisher` Signed-off-by: Abrar Rahman Protyasha --- .../include/examples_rclcpp_cbg_executor/ping_node.hpp | 4 ++-- .../include/examples_rclcpp_cbg_executor/pong_node.hpp | 4 ++-- .../src/examples_rclcpp_cbg_executor/ping_node.cpp | 4 ++-- .../src/examples_rclcpp_cbg_executor/pong_node.cpp | 4 ++-- .../multithreaded_executor/multithreaded_executor.cpp | 4 ++-- rclcpp/topics/minimal_subscriber/member_function.cpp | 2 +- .../member_function_with_topic_statistics.cpp | 4 ++-- .../member_function_with_unique_network_flow_endpoints.cpp | 4 ++-- rclcpp/topics/minimal_subscriber/not_composable.cpp | 2 +- 9 files changed, 16 insertions(+), 16 deletions(-) diff --git a/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/ping_node.hpp b/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/ping_node.hpp index d753185d..c8ec52e4 100644 --- a/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/ping_node.hpp +++ b/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/ping_node.hpp @@ -52,10 +52,10 @@ class PingNode : public rclcpp::Node void send_ping(); rclcpp::Subscription::SharedPtr high_pong_subscription_; - void high_pong_received(const std_msgs::msg::Int32::SharedPtr msg); + void high_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg); rclcpp::Subscription::SharedPtr low_pong_subscription_; - void low_pong_received(const std_msgs::msg::Int32::SharedPtr msg); + void low_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg); std::vector rtt_data_; }; diff --git a/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/pong_node.hpp b/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/pong_node.hpp index 0469e9fe..7c02628f 100644 --- a/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/pong_node.hpp +++ b/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/pong_node.hpp @@ -41,11 +41,11 @@ class PongNode : public rclcpp::Node rclcpp::Subscription::SharedPtr high_ping_subscription_; rclcpp::Publisher::SharedPtr high_pong_publisher_; - void high_ping_received(const std_msgs::msg::Int32::SharedPtr msg); + void high_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg); rclcpp::Subscription::SharedPtr low_ping_subscription_; rclcpp::Publisher::SharedPtr low_pong_publisher_; - void low_ping_received(const std_msgs::msg::Int32::SharedPtr msg); + void low_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg); static void burn_cpu_cycles(std::chrono::nanoseconds duration); }; diff --git a/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/ping_node.cpp b/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/ping_node.cpp index e1b016d2..7359503d 100644 --- a/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/ping_node.cpp +++ b/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/ping_node.cpp @@ -51,12 +51,12 @@ void PingNode::send_ping() low_ping_publisher_->publish(msg); } -void PingNode::high_pong_received(const std_msgs::msg::Int32::SharedPtr msg) +void PingNode::high_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg) { rtt_data_[msg->data].high_received_ = now(); } -void PingNode::low_pong_received(const std_msgs::msg::Int32::SharedPtr msg) +void PingNode::low_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg) { rtt_data_[msg->data].low_received_ = now(); } diff --git a/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/pong_node.cpp b/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/pong_node.cpp index 9984317c..234ba13d 100644 --- a/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/pong_node.cpp +++ b/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/pong_node.cpp @@ -58,14 +58,14 @@ rclcpp::CallbackGroup::SharedPtr PongNode::get_low_prio_callback_group() return low_prio_callback_group_; // the second callback group created in the ctor. } -void PongNode::high_ping_received(const std_msgs::msg::Int32::SharedPtr msg) +void PongNode::high_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg) { std::chrono::nanoseconds busyloop = get_nanos_from_secs_parameter(this, "high_busyloop"); burn_cpu_cycles(busyloop); high_pong_publisher_->publish(*msg); } -void PongNode::low_ping_received(const std_msgs::msg::Int32::SharedPtr msg) +void PongNode::low_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg) { std::chrono::nanoseconds busyloop = get_nanos_from_secs_parameter(this, "low_busyloop"); burn_cpu_cycles(busyloop); diff --git a/rclcpp/executors/multithreaded_executor/multithreaded_executor.cpp b/rclcpp/executors/multithreaded_executor/multithreaded_executor.cpp index 1c1e373f..2414dc32 100644 --- a/rclcpp/executors/multithreaded_executor/multithreaded_executor.cpp +++ b/rclcpp/executors/multithreaded_executor/multithreaded_executor.cpp @@ -129,7 +129,7 @@ class DualThreadedNode : public rclcpp::Node * Every time the Publisher publishes something, all subscribers to the topic get poked * This function gets called when Subscriber1 is poked (due to the std::bind we used when defining it) */ - void subscriber1_cb(const std_msgs::msg::String::SharedPtr msg) + void subscriber1_cb(const std_msgs::msg::String::ConstSharedPtr msg) { auto message_received_at = timing_string(); @@ -143,7 +143,7 @@ class DualThreadedNode : public rclcpp::Node * This function gets called when Subscriber2 is poked * Since it's running on a separate thread than Subscriber 1, it will run at (more-or-less) the same time! */ - void subscriber2_cb(const std_msgs::msg::String::SharedPtr msg) + void subscriber2_cb(const std_msgs::msg::String::ConstSharedPtr msg) { auto message_received_at = timing_string(); diff --git a/rclcpp/topics/minimal_subscriber/member_function.cpp b/rclcpp/topics/minimal_subscriber/member_function.cpp index 0f84d80d..793c3b32 100644 --- a/rclcpp/topics/minimal_subscriber/member_function.cpp +++ b/rclcpp/topics/minimal_subscriber/member_function.cpp @@ -31,7 +31,7 @@ class MinimalSubscriber : public rclcpp::Node } private: - void topic_callback(const std_msgs::msg::String::SharedPtr msg) const + void topic_callback(const std_msgs::msg::String::ConstSharedPtr msg) const { RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str()); } diff --git a/rclcpp/topics/minimal_subscriber/member_function_with_topic_statistics.cpp b/rclcpp/topics/minimal_subscriber/member_function_with_topic_statistics.cpp index 869c561c..4b678626 100644 --- a/rclcpp/topics/minimal_subscriber/member_function_with_topic_statistics.cpp +++ b/rclcpp/topics/minimal_subscriber/member_function_with_topic_statistics.cpp @@ -36,7 +36,7 @@ class MinimalSubscriberWithTopicStatistics : public rclcpp::Node // configure the topic name (default '/statistics') // options.topic_stats_options.publish_topic = "/topic_statistics" - auto callback = [this](std_msgs::msg::String::SharedPtr msg) { + auto callback = [this](std_msgs::msg::String::ConstSharedPtr msg) { this->topic_callback(msg); }; @@ -45,7 +45,7 @@ class MinimalSubscriberWithTopicStatistics : public rclcpp::Node } private: - void topic_callback(const std_msgs::msg::String::SharedPtr msg) const + void topic_callback(const std_msgs::msg::String::ConstSharedPtr msg) const { RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str()); } diff --git a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp index 5a008014..72f273a9 100644 --- a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp +++ b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp @@ -79,11 +79,11 @@ class MinimalSubscriberWithUniqueNetworkFlowEndpoints : public rclcpp::Node } private: - void topic_1_callback(const std_msgs::msg::String::SharedPtr msg) const + void topic_1_callback(const std_msgs::msg::String::ConstSharedPtr msg) const { RCLCPP_INFO(this->get_logger(), "Topic 1 news: '%s'", msg->data.c_str()); } - void topic_2_callback(const std_msgs::msg::String::SharedPtr msg) const + void topic_2_callback(const std_msgs::msg::String::ConstSharedPtr msg) const { RCLCPP_INFO(this->get_logger(), "Topic 2 news: '%s'", msg->data.c_str()); } diff --git a/rclcpp/topics/minimal_subscriber/not_composable.cpp b/rclcpp/topics/minimal_subscriber/not_composable.cpp index c94e7883..9b282cb5 100644 --- a/rclcpp/topics/minimal_subscriber/not_composable.cpp +++ b/rclcpp/topics/minimal_subscriber/not_composable.cpp @@ -22,7 +22,7 @@ rclcpp::Node::SharedPtr g_node = nullptr; * examples for the "new" recommended styles. This example is only included * for completeness because it is similar to "classic" standalone ROS nodes. */ -void topic_callback(const std_msgs::msg::String::SharedPtr msg) +void topic_callback(const std_msgs::msg::String::ConstSharedPtr msg) { RCLCPP_INFO(g_node->get_logger(), "I heard: '%s'", msg->data.c_str()); }