diff --git a/demo_nodes_cpp/src/topics/listener_loaned_message.cpp b/demo_nodes_cpp/src/topics/listener_loaned_message.cpp index cb5d867fd..f5665a801 100644 --- a/demo_nodes_cpp/src/topics/listener_loaned_message.cpp +++ b/demo_nodes_cpp/src/topics/listener_loaned_message.cpp @@ -1,4 +1,4 @@ -// Copyright 2014 Open Source Robotics Foundation, Inc. +// Copyright 2021 Open Source Robotics Foundation, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -20,34 +20,34 @@ namespace demo_nodes_cpp { - // Create a Listener class that subclasses the generic rclcpp::Node base class. - // The main function below will instantiate the class as a ROS node. - class LoanedMessageListener : public rclcpp::Node +// Create a Listener class that subclasses the generic rclcpp::Node base class. +// The main function below will instantiate the class as a ROS node. +class LoanedMessageListener : public rclcpp::Node +{ +public: + DEMO_NODES_CPP_PUBLIC + explicit LoanedMessageListener(const rclcpp::NodeOptions & options) + : Node("listener_loaned_message", options) { - public: - DEMO_NODES_CPP_PUBLIC - explicit LoanedMessageListener(const rclcpp::NodeOptions &options) - : Node("listener_loaned_message", options) - { - // Create a callback function for when messages are received. - // Variations of this function also exist using, for example UniquePtr for zero-copy transport. - setvbuf(stdout, NULL, _IONBF, BUFSIZ); - auto callback = - [this](const std_msgs::msg::Float64::SharedPtr msg) -> void + // Create a callback function for when messages are received. + // Variations of this function also exist using, for example UniquePtr for zero-copy transport. + setvbuf(stdout, NULL, _IONBF, BUFSIZ); + auto callback = + [this](const std_msgs::msg::Float64::SharedPtr msg) -> void { RCLCPP_INFO(this->get_logger(), "I heard: [%f]", msg->data); }; - // Create a subscription to the topic which can be matched with one or more compatible ROS - // publishers. - // Note that not all publishers on the same topic with the same type will be compatible: - // they must have compatible Quality of Service policies. - sub_ = create_subscription("chatter_pod", 10, callback); - } + // Create a subscription to the topic which can be matched with one or more compatible ROS + // publishers. + // Note that not all publishers on the same topic with the same type will be compatible: + // they must have compatible Quality of Service policies. + sub_ = create_subscription("chatter_pod", 10, callback); + } - private: - rclcpp::Subscription::SharedPtr sub_; - }; +private: + rclcpp::Subscription::SharedPtr sub_; +}; -} // namespace demo_nodes_cpp +} // namespace demo_nodes_cpp RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::LoanedMessageListener)