Skip to content

Commit

Permalink
Fix deprecated subscriber callbacks (#323)
Browse files Browse the repository at this point in the history
These fixes target the following packages within examples:
* `examples_rclcpp_cbg_executor`
* `multithreaded_executor`
* `minimal_subscriber`
* `minimal_publisher`

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>
  • Loading branch information
Abrar Rahman Protyasha committed Aug 23, 2021
1 parent f6e0b83 commit 669ec3e
Show file tree
Hide file tree
Showing 9 changed files with 16 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -52,10 +52,10 @@ class PingNode : public rclcpp::Node
void send_ping();

rclcpp::Subscription<std_msgs::msg::Int32>::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<std_msgs::msg::Int32>::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<RTTData> rtt_data_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,11 @@ class PongNode : public rclcpp::Node

rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr high_ping_subscription_;
rclcpp::Publisher<std_msgs::msg::Int32>::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<std_msgs::msg::Int32>::SharedPtr low_ping_subscription_;
rclcpp::Publisher<std_msgs::msg::Int32>::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);
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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();

Expand All @@ -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();

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/topics/minimal_subscriber/member_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
};

Expand All @@ -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());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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());
}
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/topics/minimal_subscriber/not_composable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
}
Expand Down

0 comments on commit 669ec3e

Please sign in to comment.