Skip to content

Commit 7af8c38

Browse files
committed
Update code based on new shutdown interface
Signed-off-by: Barry Xu <[email protected]>
1 parent 6fce3a9 commit 7af8c38

File tree

1 file changed

+8
-33
lines changed

1 file changed

+8
-33
lines changed

rclcpp/topics/minimal_publisher/member_function_with_wait_for_all_acked.cpp

Lines changed: 8 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -24,35 +24,11 @@ using namespace std::chrono_literals;
2424

2525
/* This example shows how to use wait_for_all_acked for the publisher */
2626

27-
class CustomContext : public rclcpp::Context
28-
{
29-
public:
30-
RCLCPP_SMART_PTR_DEFINITIONS(CustomContext)
31-
32-
bool shutdown(const std::string & reason) override
33-
{
34-
// Before shutdown, confirm all subscribers acknowledge sent messages
35-
if (custom_shutdown_func_) {
36-
custom_shutdown_func_();
37-
}
38-
39-
return rclcpp::Context::shutdown(reason);
40-
}
41-
42-
void set_custom_shutdown_func(std::function<void()> custom_shutdown_func)
43-
{
44-
custom_shutdown_func_ = custom_shutdown_func;
45-
}
46-
47-
private:
48-
std::function<void()> custom_shutdown_func_;
49-
};
50-
5127
class MinimalPublisher : public rclcpp::Node
5228
{
5329
public:
54-
explicit MinimalPublisher(const CustomContext::SharedPtr context)
55-
: Node("minimal_publisher_with_wait_for_all_acked", rclcpp::NodeOptions().context(context)),
30+
MinimalPublisher()
31+
: Node("minimal_publisher_with_wait_for_all_acked"),
5632
count_(0),
5733
wait_timeout_(300)
5834
{
@@ -61,7 +37,9 @@ class MinimalPublisher : public rclcpp::Node
6137
"topic",
6238
rclcpp::QoS(10).reliable());
6339

64-
context->set_custom_shutdown_func(
40+
// call wait_for_all_acked before shutdown
41+
using rclcpp::contexts::get_global_default_context;
42+
get_global_default_context()->add_pre_shutdown_callback(
6543
[this]() {
6644
this->wait_for_all_acked();
6745
});
@@ -78,7 +56,7 @@ class MinimalPublisher : public rclcpp::Node
7856
if (publisher_->wait_for_all_acked(wait_timeout_)) {
7957
RCLCPP_INFO(
8058
this->get_logger(),
81-
"All Subscribers acknowledges messages");
59+
"All subscribers acknowledge messages");
8260
} else {
8361
RCLCPP_INFO(
8462
this->get_logger(),
@@ -95,7 +73,7 @@ class MinimalPublisher : public rclcpp::Node
9573
publisher_->publish(message);
9674

9775
// After sending some messages, you can call wait_for_all_acked() to confirm all subscribers
98-
// acknowledge message.
76+
// acknowledge messages.
9977
}
10078
rclcpp::TimerBase::SharedPtr timer_;
10179
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
@@ -107,10 +85,7 @@ int main(int argc, char * argv[])
10785
{
10886
rclcpp::init(argc, argv);
10987

110-
auto custom_context = std::make_shared<CustomContext>();
111-
custom_context->init(argc, argv);
112-
113-
auto publisher = std::make_shared<MinimalPublisher>(custom_context);
88+
auto publisher = std::make_shared<MinimalPublisher>();
11489
rclcpp::spin(publisher);
11590
rclcpp::shutdown();
11691

0 commit comments

Comments
 (0)