Skip to content

Commit

Permalink
Updated based on review comments
Browse files Browse the repository at this point in the history
Signed-off-by: Barry Xu <[email protected]>
  • Loading branch information
Barry-Xu-2018 committed May 13, 2021
1 parent f6af16a commit 20cc096
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 1 deletion.
3 changes: 2 additions & 1 deletion rclcpp/include/rclcpp/publisher_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,7 @@ class PublisherBase : public std::enable_shared_from_this<PublisherBase>
* This function waits until all published message data were acknowledged by all subscribers or
* timeout.
*
* timeout must be less then std::chrono::nanoseconds::max().
* timeout must be less than std::chrono::nanoseconds::max().
* If the timeout is negative then this function will block indefinitely until all published
* message data were acknowledged.
* If the timeout is 0 then this function will be non-blocking; checking all published message
Expand All @@ -222,6 +222,7 @@ class PublisherBase : public std::enable_shared_from_this<PublisherBase>
* \return `true` if all published message data were acknowledged before timeout, otherwise
* `false`.
* \throws rclcpp::exceptions::RCLError if middleware doesn't support or internal error occurs
* \throws std::invalid_argument if timeout is greater than nanoseconds::max()
*/
template<typename DurationRepT = int64_t, typename DurationT = std::milli>
bool
Expand Down
25 changes: 25 additions & 0 deletions rclcpp/test/rclcpp/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include "../utils/rclcpp_gtest_macros.hpp"

#include "test_msgs/msg/empty.hpp"
#include "test_msgs/msg/strings.hpp"

class TestPublisher : public ::testing::Test
{
Expand Down Expand Up @@ -579,3 +580,27 @@ TEST_F(TestPublisher, check_wait_for_all_acked_return) {
rclcpp::exceptions::RCLError);
}
}

class TestPublisherWaitForAllAcked
: public TestPublisher, public ::testing::WithParamInterface<rclcpp::QoS>
{
};

TEST_P(TestPublisherWaitForAllAcked, check_wait_for_all_acked_with_QosPolicy) {
initialize();

auto do_nothing = [](std::shared_ptr<const test_msgs::msg::Strings>) {};
auto pub = node->create_publisher<test_msgs::msg::Strings>("topic", GetParam());
auto sub = node->create_subscription<test_msgs::msg::Strings>("topic", 1, do_nothing);

auto msg = std::make_shared<test_msgs::msg::Strings>();
for (int i = 0; i < 20; i++) {
ASSERT_NO_THROW(pub->publish(*msg));
}
EXPECT_TRUE(pub->wait_for_all_acked(std::chrono::milliseconds(500)));
}

INSTANTIATE_TEST_SUITE_P(
TestWaitForAllAckedWithParm,
TestPublisherWaitForAllAcked,
::testing::Values(rclcpp::QoS(1).reliable(), rclcpp::QoS(1).best_effort()));

0 comments on commit 20cc096

Please sign in to comment.