Skip to content

Commit 0088f1a

Browse files
authored
Use const& signature for read-only sub callbacks (#337)
const& signatures for read-only subscriber callbacks Signed-off-by: Abrar Rahman Protyasha <[email protected]>
1 parent 57d327c commit 0088f1a

File tree

4 files changed

+11
-11
lines changed

4 files changed

+11
-11
lines changed

rclcpp/topics/minimal_subscriber/member_function.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -31,9 +31,9 @@ class MinimalSubscriber : public rclcpp::Node
3131
}
3232

3333
private:
34-
void topic_callback(const std_msgs::msg::String::ConstSharedPtr msg) const
34+
void topic_callback(const std_msgs::msg::String & msg) const
3535
{
36-
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
36+
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
3737
}
3838
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
3939
};

rclcpp/topics/minimal_subscriber/member_function_with_topic_statistics.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ class MinimalSubscriberWithTopicStatistics : public rclcpp::Node
3636
// configure the topic name (default '/statistics')
3737
// options.topic_stats_options.publish_topic = "/topic_statistics"
3838

39-
auto callback = [this](std_msgs::msg::String::ConstSharedPtr msg) {
39+
auto callback = [this](const std_msgs::msg::String & msg) {
4040
this->topic_callback(msg);
4141
};
4242

@@ -45,9 +45,9 @@ class MinimalSubscriberWithTopicStatistics : public rclcpp::Node
4545
}
4646

4747
private:
48-
void topic_callback(const std_msgs::msg::String::ConstSharedPtr msg) const
48+
void topic_callback(const std_msgs::msg::String & msg) const
4949
{
50-
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
50+
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
5151
}
5252
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
5353
};

rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -79,13 +79,13 @@ class MinimalSubscriberWithUniqueNetworkFlowEndpoints : public rclcpp::Node
7979
}
8080

8181
private:
82-
void topic_1_callback(const std_msgs::msg::String::ConstSharedPtr msg) const
82+
void topic_1_callback(const std_msgs::msg::String & msg) const
8383
{
84-
RCLCPP_INFO(this->get_logger(), "Topic 1 news: '%s'", msg->data.c_str());
84+
RCLCPP_INFO(this->get_logger(), "Topic 1 news: '%s'", msg.data.c_str());
8585
}
86-
void topic_2_callback(const std_msgs::msg::String::ConstSharedPtr msg) const
86+
void topic_2_callback(const std_msgs::msg::String & msg) const
8787
{
88-
RCLCPP_INFO(this->get_logger(), "Topic 2 news: '%s'", msg->data.c_str());
88+
RCLCPP_INFO(this->get_logger(), "Topic 2 news: '%s'", msg.data.c_str());
8989
}
9090
/// Print network flow endpoints in JSON-like format
9191
void print_network_flow_endpoints(

rclcpp/topics/minimal_subscriber/not_composable.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,9 +22,9 @@ rclcpp::Node::SharedPtr g_node = nullptr;
2222
* examples for the "new" recommended styles. This example is only included
2323
* for completeness because it is similar to "classic" standalone ROS nodes. */
2424

25-
void topic_callback(const std_msgs::msg::String::ConstSharedPtr msg)
25+
void topic_callback(const std_msgs::msg::String & msg)
2626
{
27-
RCLCPP_INFO(g_node->get_logger(), "I heard: '%s'", msg->data.c_str());
27+
RCLCPP_INFO(g_node->get_logger(), "I heard: '%s'", msg.data.c_str());
2828
}
2929

3030
int main(int argc, char * argv[])

0 commit comments

Comments
 (0)