|
| 1 | +// Copyright 2024 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 | + |
| 15 | +#ifndef RCLCPP__TEST__RCLCPP__WAITABLES__WAITABLE_TEST_HELPERS_HPP_ |
| 16 | +#define RCLCPP__TEST__RCLCPP__WAITABLES__WAITABLE_TEST_HELPERS_HPP_ |
| 17 | + |
| 18 | +#include <gtest/gtest.h> |
| 19 | + |
| 20 | +#include <chrono> |
| 21 | +#include <functional> |
| 22 | +#include <memory> |
| 23 | + |
| 24 | +#include <rclcpp/wait_set.hpp> |
| 25 | + |
| 26 | +namespace rclcpp |
| 27 | +{ |
| 28 | +namespace test |
| 29 | +{ |
| 30 | +namespace waitables |
| 31 | +{ |
| 32 | + |
| 33 | +/// Test that a given waitable is ready after a second wait. |
| 34 | +/** |
| 35 | + * The purpose of this test is to check that a waitable will remain ready |
| 36 | + * on subsequent wait calls, if that is the expected behavior. |
| 37 | + * Not all waitables should remain ready after a wait call, which can be |
| 38 | + * expressed in the expected_to_stay_ready argument which defaults to true. |
| 39 | + * If set to false, it will check that it is not ready after a second wait, as |
| 40 | + * well as some other parts of the test. |
| 41 | + * |
| 42 | + * The given waitable should: |
| 43 | + * |
| 44 | + * - not be ready initially |
| 45 | + * - not be ready after being waited on (and timing out) |
| 46 | + * - should become ready after the make_waitable_ready method is called |
| 47 | + * - may or may not be ready at this point |
| 48 | + * - should be ready after waiting on it, within the wait_timeout |
| 49 | + * - should be ready still after a second wait (unless expected_to_stay_ready = false) |
| 50 | + * - if expected_to_stay_ready, should become not ready after a take_data/execute |
| 51 | + */ |
| 52 | +template<typename WaitableT> |
| 53 | +void |
| 54 | +do_test_that_waitable_stays_ready_after_second_wait( |
| 55 | + const std::shared_ptr<WaitableT> & waitable, |
| 56 | + std::function<void()> make_waitable_ready, |
| 57 | + bool expected_to_stay_ready = true, |
| 58 | + std::chrono::nanoseconds wait_timeout = std::chrono::seconds(5)) |
| 59 | +{ |
| 60 | + rclcpp::WaitSet wait_set; |
| 61 | + wait_set.add_waitable(waitable); |
| 62 | + |
| 63 | + // not ready initially |
| 64 | + EXPECT_FALSE(waitable->is_ready(&wait_set.get_rcl_wait_set())) |
| 65 | + << "waitable is unexpectedly ready before waiting"; |
| 66 | + |
| 67 | + // not ready after a wait that timesout |
| 68 | + { |
| 69 | + auto wait_result = wait_set.wait(std::chrono::seconds(0)); |
| 70 | + EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Timeout) |
| 71 | + << "wait set did not timeout as expected"; |
| 72 | + EXPECT_FALSE(waitable->is_ready(&wait_set.get_rcl_wait_set())) |
| 73 | + << "waitable is unexpectedly ready after waiting, but before making ready"; |
| 74 | + } |
| 75 | + |
| 76 | + // make it ready and wait on it |
| 77 | + make_waitable_ready(); |
| 78 | + { |
| 79 | + auto wait_result = wait_set.wait(wait_timeout); |
| 80 | + EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Ready) |
| 81 | + << "wait set was not ready after the waitable should have been made ready"; |
| 82 | + EXPECT_TRUE(waitable->is_ready(&wait_set.get_rcl_wait_set())) |
| 83 | + << "waitable is unexpectedly not ready after making it ready and waiting"; |
| 84 | + } |
| 85 | + |
| 86 | + // wait again, and see that it is ready as expected or not expected |
| 87 | + { |
| 88 | + auto wait_result = wait_set.wait(std::chrono::seconds(0)); |
| 89 | + if (expected_to_stay_ready) { |
| 90 | + EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Ready) |
| 91 | + << "wait set was not ready on a second wait on the waitable"; |
| 92 | + EXPECT_TRUE(waitable->is_ready(&wait_set.get_rcl_wait_set())) |
| 93 | + << "waitable unexpectedly not ready after second wait"; |
| 94 | + } else { |
| 95 | + EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Timeout) |
| 96 | + << "wait set did not time out after the waitable should have no longer been ready"; |
| 97 | + EXPECT_FALSE(waitable->is_ready(&wait_set.get_rcl_wait_set())) |
| 98 | + << "waitable was ready after waiting a second time, which was not expected"; |
| 99 | + } |
| 100 | + } |
| 101 | + |
| 102 | + // if expected_to_stay_ready, check that take_data/execute makes it not ready |
| 103 | + if (expected_to_stay_ready) { |
| 104 | + waitable->execute(waitable->take_data()); |
| 105 | + auto wait_result = wait_set.wait(std::chrono::seconds(0)); |
| 106 | + EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Timeout) |
| 107 | + << "wait set did not time out after the waitable should have no longer been ready"; |
| 108 | + EXPECT_FALSE(waitable->is_ready(&wait_set.get_rcl_wait_set())) |
| 109 | + << "waitable was unexpectedly ready after a take_data and execute"; |
| 110 | + } |
| 111 | +} |
| 112 | + |
| 113 | +} // namespace waitables |
| 114 | +} // namespace test |
| 115 | +} // namespace rclcpp |
| 116 | + |
| 117 | +#endif // RCLCPP__TEST__RCLCPP__WAITABLES__WAITABLE_TEST_HELPERS_HPP_ |
0 commit comments