|
20 | 20 |
|
21 | 21 | namespace demo_nodes_cpp
|
22 | 22 | {
|
23 |
| - // Create a Listener class that subclasses the generic rclcpp::Node base class. |
24 |
| - // The main function below will instantiate the class as a ROS node. |
25 |
| - class LoanedMessageListener : public rclcpp::Node |
| 23 | +// Create a Listener class that subclasses the generic rclcpp::Node base class. |
| 24 | +// The main function below will instantiate the class as a ROS node. |
| 25 | +class LoanedMessageListener : public rclcpp::Node |
| 26 | +{ |
| 27 | +public: |
| 28 | + DEMO_NODES_CPP_PUBLIC |
| 29 | + explicit LoanedMessageListener(const rclcpp::NodeOptions &options) |
| 30 | + : Node("listener_loaned_message", options) |
26 | 31 | {
|
27 |
| - public: |
28 |
| - DEMO_NODES_CPP_PUBLIC |
29 |
| - explicit LoanedMessageListener(const rclcpp::NodeOptions &options) |
30 |
| - : Node("listener_loaned_message", options) |
| 32 | + // Create a callback function for when messages are received. |
| 33 | + // Variations of this function also exist using, for example UniquePtr for zero-copy transport. |
| 34 | + setvbuf(stdout, NULL, _IONBF, BUFSIZ); |
| 35 | + auto callback = |
| 36 | + [this](const std_msgs::msg::Float64::SharedPtr msg) -> void |
31 | 37 | {
|
32 |
| - // Create a callback function for when messages are received. |
33 |
| - // Variations of this function also exist using, for example UniquePtr for zero-copy transport. |
34 |
| - setvbuf(stdout, NULL, _IONBF, BUFSIZ); |
35 |
| - auto callback = |
36 |
| - [this](const std_msgs::msg::Float64::SharedPtr msg) -> void |
37 |
| - { |
38 |
| - RCLCPP_INFO(this->get_logger(), "I heard: [%f]", msg->data); |
39 |
| - }; |
40 |
| - // Create a subscription to the topic which can be matched with one or more compatible ROS |
41 |
| - // publishers. |
42 |
| - // Note that not all publishers on the same topic with the same type will be compatible: |
43 |
| - // they must have compatible Quality of Service policies. |
44 |
| - sub_ = create_subscription<std_msgs::msg::Float64>("chatter_pod", 10, callback); |
45 |
| - } |
| 38 | + RCLCPP_INFO(this->get_logger(), "I heard: [%f]", msg->data); |
| 39 | + }; |
| 40 | + // Create a subscription to the topic which can be matched with one or more compatible ROS |
| 41 | + // publishers. |
| 42 | + // Note that not all publishers on the same topic with the same type will be compatible: |
| 43 | + // they must have compatible Quality of Service policies. |
| 44 | + sub_ = create_subscription<std_msgs::msg::Float64>("chatter_pod", 10, callback); |
| 45 | + } |
46 | 46 |
|
47 |
| - private: |
48 |
| - rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr sub_; |
49 |
| - }; |
| 47 | +private: |
| 48 | + rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr sub_; |
| 49 | +}; |
50 | 50 |
|
51 |
| -} // namespace demo_nodes_cpp |
| 51 | +} // namespace demo_nodes_cpp |
52 | 52 |
|
53 | 53 | RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::LoanedMessageListener)
|
0 commit comments