|
| 1 | +// Copyright 2021 Open Source Robotics Foundation, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | +#include <chrono> |
| 15 | +#include <functional> |
| 16 | +#include <cinttypes> |
| 17 | +#include <memory> |
| 18 | +#include <string> |
| 19 | + |
| 20 | +#include "rclcpp/rclcpp.hpp" |
| 21 | +#include "std_msgs/msg/string.hpp" |
| 22 | + |
| 23 | +using namespace std::chrono_literals; |
| 24 | + |
| 25 | +/* This example shows how to use wait_for_all_acked for the publisher */ |
| 26 | + |
| 27 | +class MinimalPublisher : public rclcpp::Node |
| 28 | +{ |
| 29 | +public: |
| 30 | + MinimalPublisher() |
| 31 | + : Node("minimal_publisher_with_wait_for_all_acked"), |
| 32 | + count_(0), |
| 33 | + wait_timeout_(300) |
| 34 | + { |
| 35 | + // publisher must set reliable mode |
| 36 | + publisher_ = this->create_publisher<std_msgs::msg::String>( |
| 37 | + "topic", |
| 38 | + rclcpp::QoS(10).reliable()); |
| 39 | + |
| 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( |
| 43 | + [this]() { |
| 44 | + this->timer_->cancel(); |
| 45 | + this->wait_for_all_acked(); |
| 46 | + }); |
| 47 | + |
| 48 | + timer_ = this->create_wall_timer( |
| 49 | + 500ms, std::bind(&MinimalPublisher::timer_callback, this)); |
| 50 | + } |
| 51 | + |
| 52 | +private: |
| 53 | + void wait_for_all_acked() |
| 54 | + { |
| 55 | + // Confirm all subscribers receive sent messages. |
| 56 | + // Note that if no subscription is connected, wait_for_all_acked() always return true. |
| 57 | + if (publisher_->wait_for_all_acked(wait_timeout_)) { |
| 58 | + RCLCPP_INFO( |
| 59 | + this->get_logger(), |
| 60 | + "All subscribers acknowledge messages"); |
| 61 | + } else { |
| 62 | + RCLCPP_INFO( |
| 63 | + this->get_logger(), |
| 64 | + "Not all subscribers acknowledge messages during %" PRId64 " ms", |
| 65 | + static_cast<int64_t>(wait_timeout_.count())); |
| 66 | + } |
| 67 | + } |
| 68 | + |
| 69 | + void timer_callback() |
| 70 | + { |
| 71 | + auto message = std_msgs::msg::String(); |
| 72 | + message.data = "Hello, world! " + std::to_string(count_++); |
| 73 | + RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()); |
| 74 | + publisher_->publish(message); |
| 75 | + |
| 76 | + // After sending some messages, you can call wait_for_all_acked() to confirm all subscribers |
| 77 | + // acknowledge messages. |
| 78 | + } |
| 79 | + rclcpp::TimerBase::SharedPtr timer_; |
| 80 | + rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_; |
| 81 | + size_t count_; |
| 82 | + std::chrono::milliseconds wait_timeout_; |
| 83 | +}; |
| 84 | + |
| 85 | +int main(int argc, char * argv[]) |
| 86 | +{ |
| 87 | + rclcpp::init(argc, argv); |
| 88 | + |
| 89 | + auto publisher = std::make_shared<MinimalPublisher>(); |
| 90 | + rclcpp::spin(publisher); |
| 91 | + rclcpp::shutdown(); |
| 92 | + |
| 93 | + return 0; |
| 94 | +} |
0 commit comments