-
Notifications
You must be signed in to change notification settings - Fork 331
/
talker.cpp
72 lines (62 loc) · 2.46 KB
/
talker.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
// Copyright 2014 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.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <chrono>
#include <cstdio>
#include <memory>
#include <utility>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"
#include "std_msgs/msg/string.hpp"
#include "demo_nodes_cpp/visibility_control.h"
using namespace std::chrono_literals;
namespace demo_nodes_cpp
{
// Create a Talker class that subclasses the generic rclcpp::Node base class.
// The main function below will instantiate the class as a ROS node.
class Talker : public rclcpp::Node
{
public:
DEMO_NODES_CPP_PUBLIC
explicit Talker(const rclcpp::NodeOptions & options)
: Node("talker", options)
{
// Create a function for when messages are to be sent.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
auto publish_message =
[this]() -> void
{
msg_ = std::make_unique<std_msgs::msg::String>();
msg_->data = "Hello World: " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg_->data.c_str());
// Put the message into a queue to be processed by the middleware.
// This call is non-blocking.
pub_->publish(std::move(msg_));
};
// Create a publisher with a custom Quality of Service profile.
// Uniform initialization is suggested so it can be trivially changed to
// rclcpp::KeepAll{} if the user wishes.
// (rclcpp::KeepLast(7) -> rclcpp::KeepAll() fails to compile)
rclcpp::QoS qos(rclcpp::KeepLast{7});
pub_ = this->create_publisher<std_msgs::msg::String>("chatter", qos);
// Use a timer to schedule periodic message publishing.
timer_ = this->create_wall_timer(1s, publish_message);
}
private:
size_t count_ = 1;
std::unique_ptr<std_msgs::msg::String> msg_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
rclcpp::TimerBase::SharedPtr timer_;
};
} // namespace demo_nodes_cpp
RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::Talker)