-
Notifications
You must be signed in to change notification settings - Fork 34
/
Copy pathpublisher_main.cpp
62 lines (47 loc) · 1.56 KB
/
publisher_main.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
#include <memory>
#include <iostream>
#include <thread>
#include <sstream>
#include "rclcpp/rclcpp.hpp"
#include "simple_backward_compatible/msg/optional_fields.hpp"
using namespace std::chrono_literals;
using OptionalFieldsMsg = simple_backward_compatible::msg::OptionalFields;
class SimplePublisherNode : public rclcpp::Node
{
public:
SimplePublisherNode() : Node("publisher_node")
{
_publisher = this->create_publisher<OptionalFieldsMsg>("my_topic", 10);
auto period = 500ms;
_timer = this->create_wall_timer(period, std::bind(&SimplePublisherNode::publish, this));
_count = 0;
}
void publish()
{
auto message = std::make_unique<OptionalFieldsMsg>();
_count ++;
message->data = "Hello, world! " + std::to_string(_count);
#ifdef BUILD_V2
message->optional_boolean.push_back(true);
message->optional_vector = { 10, 20, 30 };
#endif
_publisher->publish(std::move(message));
#ifdef BUILD_V2
RCLCPP_INFO(this->get_logger(), "Publishing VERSION2: '%s'", message->data.c_str());
#else
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message->data.c_str());
#endif
}
private:
rclcpp::Publisher<OptionalFieldsMsg>::SharedPtr _publisher;
rclcpp::TimerBase::SharedPtr _timer;
int _count;
};
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
std::shared_ptr<SimplePublisherNode> node = std::make_shared<SimplePublisherNode>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}