generated from icsl-Jeon/simple-ros2-package
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathmulti_thread_reentrant_subscriber_node.cc
76 lines (61 loc) · 2.49 KB
/
multi_thread_reentrant_subscriber_node.cc
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
73
74
75
76
#include <chrono>
#include <random>
#include <thread>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>
using namespace std::chrono_literals;
class MultiThreadReentrantSubscriber : public rclcpp::Node {
public:
MultiThreadReentrantSubscriber() : Node("subscriber_node") {
rclcpp::SubscriptionOptions options;
options.callback_group =
create_callback_group(rclcpp::CallbackGroupType::Reentrant);
short_subscriber_ = create_subscription<std_msgs::msg::String>(
"/short_topic", rclcpp::QoS(10),
std::bind(&MultiThreadReentrantSubscriber::ShortTopicCallback, this,
std::placeholders::_1),
options);
long_subscriber_ = create_subscription<std_msgs::msg::String>(
"/long_topic", rclcpp::QoS(10),
std::bind(&MultiThreadReentrantSubscriber::LongTopicCallback, this,
std::placeholders::_1),
options);
}
private:
std::string processed_short_string_;
std::string processed_long_string_;
std::string ProcessString(const std::string &raw_string);
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr short_subscriber_;
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr long_subscriber_;
void ShortTopicCallback(const std_msgs::msg::String::SharedPtr msg);
void LongTopicCallback(const std_msgs::msg::String::SharedPtr msg);
};
std::string
MultiThreadReentrantSubscriber::ProcessString(const std::string &raw_string) {
std::thread::id this_id = std::this_thread::get_id();
std::ostringstream oss;
oss << std::this_thread::get_id();
std::this_thread::sleep_for(std::chrono::seconds(2));
return "** " + raw_string + " **" + " ( by " + oss.str() + ") ";
};
void MultiThreadReentrantSubscriber::ShortTopicCallback(
const std_msgs::msg::String::SharedPtr msg) {
auto processed_string = ProcessString(msg->data);
RCLCPP_INFO(get_logger(), "Setting processed: %s", processed_string.c_str());
processed_short_string_ = processed_string;
}
void MultiThreadReentrantSubscriber::LongTopicCallback(
const std_msgs::msg::String::SharedPtr msg) {
auto processed_string = ProcessString(msg->data);
RCLCPP_INFO(get_logger(), "Setting processed: %s", processed_string.c_str());
processed_long_string_ = processed_string;
}
int main(int argc, char **argv) {
rclcpp::init(argc, argv);
auto node = std::make_shared<MultiThreadReentrantSubscriber>();
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(node);
executor.spin();
rclcpp::shutdown();
return 0;
}