Skip to content

Commit 20cc096

Browse files
committed
Updated based on review comments
Signed-off-by: Barry Xu <barry.xu@sony.com>
1 parent f6af16a commit 20cc096

File tree

2 files changed

+27
-1
lines changed

2 files changed

+27
-1
lines changed

rclcpp/include/rclcpp/publisher_base.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -209,7 +209,7 @@ class PublisherBase : public std::enable_shared_from_this<PublisherBase>
209209
* This function waits until all published message data were acknowledged by all subscribers or
210210
* timeout.
211211
*
212-
* timeout must be less then std::chrono::nanoseconds::max().
212+
* timeout must be less than std::chrono::nanoseconds::max().
213213
* If the timeout is negative then this function will block indefinitely until all published
214214
* message data were acknowledged.
215215
* If the timeout is 0 then this function will be non-blocking; checking all published message
@@ -222,6 +222,7 @@ class PublisherBase : public std::enable_shared_from_this<PublisherBase>
222222
* \return `true` if all published message data were acknowledged before timeout, otherwise
223223
* `false`.
224224
* \throws rclcpp::exceptions::RCLError if middleware doesn't support or internal error occurs
225+
* \throws std::invalid_argument if timeout is greater than nanoseconds::max()
225226
*/
226227
template<typename DurationRepT = int64_t, typename DurationT = std::milli>
227228
bool

rclcpp/test/rclcpp/test_publisher.cpp

+25
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@
2929
#include "../utils/rclcpp_gtest_macros.hpp"
3030

3131
#include "test_msgs/msg/empty.hpp"
32+
#include "test_msgs/msg/strings.hpp"
3233

3334
class TestPublisher : public ::testing::Test
3435
{
@@ -579,3 +580,27 @@ TEST_F(TestPublisher, check_wait_for_all_acked_return) {
579580
rclcpp::exceptions::RCLError);
580581
}
581582
}
583+
584+
class TestPublisherWaitForAllAcked
585+
: public TestPublisher, public ::testing::WithParamInterface<rclcpp::QoS>
586+
{
587+
};
588+
589+
TEST_P(TestPublisherWaitForAllAcked, check_wait_for_all_acked_with_QosPolicy) {
590+
initialize();
591+
592+
auto do_nothing = [](std::shared_ptr<const test_msgs::msg::Strings>) {};
593+
auto pub = node->create_publisher<test_msgs::msg::Strings>("topic", GetParam());
594+
auto sub = node->create_subscription<test_msgs::msg::Strings>("topic", 1, do_nothing);
595+
596+
auto msg = std::make_shared<test_msgs::msg::Strings>();
597+
for (int i = 0; i < 20; i++) {
598+
ASSERT_NO_THROW(pub->publish(*msg));
599+
}
600+
EXPECT_TRUE(pub->wait_for_all_acked(std::chrono::milliseconds(500)));
601+
}
602+
603+
INSTANTIATE_TEST_SUITE_P(
604+
TestWaitForAllAckedWithParm,
605+
TestPublisherWaitForAllAcked,
606+
::testing::Values(rclcpp::QoS(1).reliable(), rclcpp::QoS(1).best_effort()));

0 commit comments

Comments
 (0)