Skip to content

Commit

Permalink
Split test_executors.cpp even further. (#2572)
Browse files Browse the repository at this point in the history
That's because it is too large for Windows Debug to compile,
so split into smaller bits.

Even with this split, the file is too big; that's likely
because we are using TYPED_TEST here, which generates multiple
symbols per test case.  To deal with this, without further
breaking up the file, also add in the /bigobj flag when
compiling on Windows Debug.

Signed-off-by: Chris Lalancette <clalancette@gmail.com>
(cherry picked from commit c743c17)
  • Loading branch information
clalancette committed Sep 4, 2024
1 parent 1b44854 commit f22dc10
Show file tree
Hide file tree
Showing 5 changed files with 396 additions and 260 deletions.
14 changes: 14 additions & 0 deletions rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -462,8 +462,12 @@ endif()
ament_add_gtest(
test_executors
executors/test_executors.cpp
executors/test_waitable.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}"
TIMEOUT 180)
if(CMAKE_BUILD_TYPE STREQUAL "Debug" AND MSVC)
target_compile_options(test_executors PRIVATE "/bigobj")
endif()
if(TARGET test_executors)
target_link_libraries(test_executors ${PROJECT_NAME} rcl::rcl ${test_msgs_TARGETS})
endif()
Expand Down Expand Up @@ -495,6 +499,16 @@ if(TARGET test_executors)
target_link_libraries(test_executors_intraprocess ${PROJECT_NAME} ${test_msgs_TARGETS})
endif()

ament_add_gtest(
test_executors_busy_waiting
executors/test_executors_busy_waiting.cpp
executors/test_waitable.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}"
TIMEOUT 180)
if(TARGET test_executors_busy_waiting)
target_link_libraries(test_executors_busy_waiting ${PROJECT_NAME})
endif()

ament_add_gtest(test_static_single_threaded_executor executors/test_static_single_threaded_executor.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}")
if(TARGET test_static_single_threaded_executor)
Expand Down
261 changes: 1 addition & 260 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
#include "test_msgs/srv/empty.hpp"

#include "./executor_types.hpp"
#include "./test_waitable.hpp"

using namespace std::chrono_literals;

Expand Down Expand Up @@ -332,114 +333,6 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteWithTimeout)
spinner.join();
}

class TestWaitable : public rclcpp::Waitable
{
public:
TestWaitable() = default;

void
add_to_wait_set(rcl_wait_set_t & wait_set) override
{
if (trigger_count_ > 0) {
// Keep the gc triggered until the trigger count is reduced back to zero.
// This is necessary if trigger() results in the wait set waking, but not
// executing this waitable, in which case it needs to be re-triggered.
gc_.trigger();
}
rclcpp::detail::add_guard_condition_to_rcl_wait_set(wait_set, gc_);
}

void trigger()
{
trigger_count_++;
gc_.trigger();
}

bool
is_ready(const rcl_wait_set_t & wait_set) override
{
is_ready_count_++;
for (size_t i = 0; i < wait_set.size_of_guard_conditions; ++i) {
auto rcl_guard_condition = wait_set.guard_conditions[i];
if (&gc_.get_rcl_guard_condition() == rcl_guard_condition) {
return true;
}
}
return false;
}

std::shared_ptr<void>
take_data() override
{
return nullptr;
}

std::shared_ptr<void>
take_data_by_entity_id(size_t id) override
{
(void) id;
return nullptr;
}

void
execute(const std::shared_ptr<void> &) override
{
trigger_count_--;
count_++;
if (nullptr != on_execute_callback_) {
on_execute_callback_();
} else {
// TODO(wjwwood): I don't know why this was here, but probably it should
// not be there, or test cases where that is important should use the
// on_execute_callback?
std::this_thread::sleep_for(3ms);
}
}

void
set_on_execute_callback(std::function<void()> on_execute_callback)
{
on_execute_callback_ = on_execute_callback;
}

void
set_on_ready_callback(std::function<void(size_t, int)> callback) override
{
auto gc_callback = [callback](size_t count) {
callback(count, 0);
};
gc_.set_on_trigger_callback(gc_callback);
}

void
clear_on_ready_callback() override
{
gc_.set_on_trigger_callback(nullptr);
}

size_t
get_number_of_ready_guard_conditions() override {return 1;}

size_t
get_count() const
{
return count_;
}

size_t
get_is_ready_call_count() const
{
return is_ready_count_;
}

private:
std::atomic<size_t> trigger_count_ = 0;
std::atomic<size_t> is_ready_count_ = 0;
std::atomic<size_t> count_ = 0;
rclcpp::GuardCondition gc_;
std::function<void()> on_execute_callback_ = nullptr;
};

TYPED_TEST(TestExecutors, spinAll)
{
using ExecutorType = TypeParam;
Expand Down Expand Up @@ -902,155 +795,3 @@ TYPED_TEST(TestExecutors, release_ownership_entity_after_spinning_cancel)

EXPECT_EQ(server.use_count(), 1);
}

template<typename T>
class TestBusyWaiting : public ::testing::Test
{
public:
void SetUp() override
{
rclcpp::init(0, nullptr);

const auto test_info = ::testing::UnitTest::GetInstance()->current_test_info();
std::stringstream test_name;
test_name << test_info->test_case_name() << "_" << test_info->name();
node = std::make_shared<rclcpp::Node>("node", test_name.str());
callback_group = node->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive,
/* automatically_add_to_executor_with_node =*/ false);

auto waitable_interfaces = node->get_node_waitables_interface();
waitable = std::make_shared<TestWaitable>();
waitable_interfaces->add_waitable(waitable, callback_group);

executor = std::make_shared<T>();
executor->add_callback_group(callback_group, node->get_node_base_interface());
}

void TearDown() override
{
rclcpp::shutdown();
}

void
set_up_and_trigger_waitable(std::function<void()> extra_callback = nullptr)
{
this->has_executed = false;
this->waitable->set_on_execute_callback([this, extra_callback]() {
if (!this->has_executed) {
// trigger once to see if the second trigger is handled or not
// this follow up trigger simulates new entities becoming ready while
// the executor is executing something else, e.g. subscription got data
// or a timer expired, etc.
// spin_some would not handle this second trigger, since it collects
// work only once, whereas spin_all should handle it since it
// collects work multiple times
this->waitable->trigger();
this->has_executed = true;
}
if (nullptr != extra_callback) {
extra_callback();
}
});
this->waitable->trigger();
}

void
check_for_busy_waits(std::chrono::steady_clock::time_point start_time)
{
// rough time based check, since the work to be done was very small it
// should be safe to check that we didn't use more than half the
// max duration, which itself is much larger than necessary
// however, it could still produce a false-positive
EXPECT_LT(
std::chrono::steady_clock::now() - start_time,
max_duration / 2)
<< "executor took a long time to execute when it should have done "
<< "nothing and should not have blocked either, but this could be a "
<< "false negative if the computer is really slow";

// this check is making some assumptions about the implementation of the
// executors, but it should be safe to say that a busy wait may result in
// hundreds or thousands of calls to is_ready(), but "normal" executor
// behavior should be within an order of magnitude of the number of
// times that the waitable was executed
ASSERT_LT(waitable->get_is_ready_call_count(), 10u * this->waitable->get_count());
}

static constexpr auto max_duration = 10s;

rclcpp::Node::SharedPtr node;
rclcpp::CallbackGroup::SharedPtr callback_group;
std::shared_ptr<TestWaitable> waitable;
std::chrono::steady_clock::time_point start_time;
std::shared_ptr<T> executor;
bool has_executed;
};

TYPED_TEST_SUITE(TestBusyWaiting, ExecutorTypes, ExecutorTypeNames);

TYPED_TEST(TestBusyWaiting, test_spin_all)
{
this->set_up_and_trigger_waitable();

auto start_time = std::chrono::steady_clock::now();
this->executor->spin_all(this->max_duration);
this->check_for_busy_waits(start_time);
// this should get the initial trigger, and the follow up from in the callback
ASSERT_EQ(this->waitable->get_count(), 2u);
}

TYPED_TEST(TestBusyWaiting, test_spin_some)
{
this->set_up_and_trigger_waitable();

auto start_time = std::chrono::steady_clock::now();
this->executor->spin_some(this->max_duration);
this->check_for_busy_waits(start_time);
// this should get the inital trigger, but not the follow up in the callback
ASSERT_EQ(this->waitable->get_count(), 1u);
}

TYPED_TEST(TestBusyWaiting, test_spin)
{
std::condition_variable cv;
std::mutex cv_m;
bool first_check_passed = false;

this->set_up_and_trigger_waitable([&cv, &cv_m, &first_check_passed]() {
cv.notify_one();
if (!first_check_passed) {
std::unique_lock<std::mutex> lk(cv_m);
cv.wait_for(lk, 1s, [&]() {return first_check_passed;});
}
});

auto start_time = std::chrono::steady_clock::now();
std::thread t([this]() {
this->executor->spin();
});

// wait until thread has started (first execute of waitable)
{
std::unique_lock<std::mutex> lk(cv_m);
cv.wait_for(lk, 10s);
}
EXPECT_GT(this->waitable->get_count(), 0u);

first_check_passed = true;
cv.notify_one();

// wait until the executor has finished (second execute of waitable)
{
std::unique_lock<std::mutex> lk(cv_m);
cv.wait_for(lk, 10s);
}
EXPECT_EQ(this->waitable->get_count(), 2u);

this->executor->cancel();
t.join();

this->check_for_busy_waits(start_time);
// this should get the initial trigger, and the follow up from in the callback
ASSERT_EQ(this->waitable->get_count(), 2u);
}
Loading

0 comments on commit f22dc10

Please sign in to comment.