Skip to content

Commit

Permalink
move executor tests to a new file
Browse files Browse the repository at this point in the history
Signed-off-by: Alberto Soragna <[email protected]>
  • Loading branch information
alsora committed Aug 4, 2024
1 parent 8591223 commit 77ddcd1
Show file tree
Hide file tree
Showing 3 changed files with 150 additions and 85 deletions.
10 changes: 10 additions & 0 deletions rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -500,6 +500,16 @@ if(TARGET test_executors)
target_link_libraries(test_executors_busy_waiting ${PROJECT_NAME})
endif()

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

ament_add_gtest(test_static_single_threaded_executor executors/test_static_single_threaded_executor.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}")
ament_add_test_label(test_static_single_threaded_executor mimick)
Expand Down
85 changes: 0 additions & 85 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -856,88 +856,3 @@ TYPED_TEST(TestExecutors, release_ownership_entity_after_spinning_cancel)

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

// This test verifies that spin_all is correctly collecting work multiple times
// even when one of the items of work is a notifier waitable event and thus results in
// rebuilding the entities collection.
// When spin_all goes back to collect more work, it should see the ready items from
// the new added entities
TYPED_TEST(TestExecutors, spin_all_doesnt_require_warmup)
{
using ExecutorType = TypeParam;
ExecutorType executor;

// Enable intra-process to guarantee deterministic and synchronous delivery of the message / event
auto node_options = rclcpp::NodeOptions().use_intra_process_comms(true);
auto node = std::make_shared<rclcpp::Node>("test_node", node_options);

// Add node to the executor before creating the entities
executor.add_node(node);

// Create entities, this will produce a notifier waitable event, telling the executor to refresh
// the entities collection
auto publisher = node->create_publisher<test_msgs::msg::Empty>("test_topic", rclcpp::QoS(10));
auto callback = [this](test_msgs::msg::Empty::ConstSharedPtr) {this->callback_count++;};
auto subscription =
node->create_subscription<test_msgs::msg::Empty>(
"test_topic", rclcpp::QoS(10), std::move(callback));

ASSERT_EQ(this->callback_count, 0u);

// Publish a message so that the new entities (i.e. the subscriber) already have work to do
publisher->publish(test_msgs::msg::Empty());

// We need to select a duration that is greater than
// the time taken to refresh the entities collection and rebuild the waitset.
// spin-all is expected to process the notifier waitable event, rebuild the collection,
// and then collect more work, finding the subscription message event.
// This duration has been selected empirically.
executor.spin_all(std::chrono::milliseconds(500));

// Verify that the callback is called as part of the spin above
EXPECT_EQ(this->callback_count, 1u);
}

// Same test as `spin_all_doesnt_require_warmup`, but uses a callback group
// This test reproduces the bug reported by https://github.com/ros2/rclcpp/issues/2589
TYPED_TEST(TestExecutors, spin_all_doesnt_require_warmup_with_cbgroup)
{
using ExecutorType = TypeParam;
ExecutorType executor;

// Enable intra-process to guarantee deterministic and synchronous delivery of the message / event
auto node_options = rclcpp::NodeOptions().use_intra_process_comms(true);
auto node = std::make_shared<rclcpp::Node>("test_node", node_options);

auto callback_group = node->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive,
false);

// Add callback group to the executor before creating the entities
executor.add_callback_group(callback_group, node->get_node_base_interface());

// Create entities, this will produce a notifier waitable event, telling the executor to refresh
// the entities collection
auto publisher = node->create_publisher<test_msgs::msg::Empty>("test_topic", rclcpp::QoS(10));
auto callback = [this](test_msgs::msg::Empty::ConstSharedPtr) {this->callback_count++;};
rclcpp::SubscriptionOptions sub_options;
sub_options.callback_group = callback_group;
auto subscription =
node->create_subscription<test_msgs::msg::Empty>(
"test_topic", rclcpp::QoS(10), std::move(callback), sub_options);

ASSERT_EQ(this->callback_count, 0u);

// Publish a message so that the new entities (i.e. the subscriber) already have work to do
publisher->publish(test_msgs::msg::Empty());

// We need to select a duration that is greater than
// the time taken to refresh the entities collection and rebuild the waitset.
// spin-all is expected to process the notifier waitable event, rebuild the collection,
// and then collect more work, finding the subscription message event.
// This duration has been selected empirically.
executor.spin_all(std::chrono::milliseconds(500));

// Verify that the callback is called as part of the spin above
EXPECT_EQ(this->callback_count, 1u);
}
140 changes: 140 additions & 0 deletions rclcpp/test/rclcpp/executors/test_executors_minimal_init.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,140 @@
// Copyright 2017 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

/**
* This test checks all implementations of rclcpp::executor to check they pass they basic API
* tests. Anything specific to any executor in particular should go in a separate test file.
*/

#include <gtest/gtest.h>

#include <chrono>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"

#include "test_msgs/msg/empty.hpp"

#include "./executor_types.hpp"

using namespace std::chrono_literals;

/**
* @brief This test suite is meant to be used by Executors tests that
* require test-specific initialization routines.
*/
template<typename T>
class TestExecutorsMinimalInitialization : public ::testing::Test
{
public:
void SetUp()
{
rclcpp::init(0, nullptr);
}

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

TYPED_TEST_SUITE(TestExecutorsMinimalInitialization, ExecutorTypes, ExecutorTypeNames);

// This test verifies that spin_all is correctly collecting work multiple times
// even when one of the items of work is a notifier waitable event and thus results in
// rebuilding the entities collection.
// When spin_all goes back to collect more work, it should see the ready items from
// the new added entities
TYPED_TEST(TestExecutorsMinimalInitialization, spin_all_doesnt_require_warmup)
{
using ExecutorType = TypeParam;
ExecutorType executor;

// Enable intra-process to guarantee deterministic and synchronous delivery of the message / event
auto node_options = rclcpp::NodeOptions().use_intra_process_comms(true);
auto node = std::make_shared<rclcpp::Node>("test_node", node_options);

// Add node to the executor before creating the entities
executor.add_node(node);

// Create entities, this will produce a notifier waitable event, telling the executor to refresh
// the entities collection
auto publisher = node->create_publisher<test_msgs::msg::Empty>("test_topic", rclcpp::QoS(10));
size_t callback_count = 0;
auto callback = [&callback_count](test_msgs::msg::Empty::ConstSharedPtr) {callback_count++;};
auto subscription =
node->create_subscription<test_msgs::msg::Empty>(
"test_topic", rclcpp::QoS(10), std::move(callback));

ASSERT_EQ(callback_count, 0u);

// Publish a message so that the new entities (i.e. the subscriber) already have work to do
publisher->publish(test_msgs::msg::Empty());

// We need to select a duration that is greater than
// the time taken to refresh the entities collection and rebuild the waitset.
// spin-all is expected to process the notifier waitable event, rebuild the collection,
// and then collect more work, finding the subscription message event.
// This duration has been selected empirically.
executor.spin_all(std::chrono::milliseconds(500));

// Verify that the callback is called as part of the spin above
EXPECT_EQ(callback_count, 1u);
}

// Same test as `spin_all_doesnt_require_warmup`, but uses a callback group
// This test reproduces the bug reported by https://github.com/ros2/rclcpp/issues/2589
TYPED_TEST(TestExecutorsMinimalInitialization, spin_all_doesnt_require_warmup_with_cbgroup)
{
using ExecutorType = TypeParam;
ExecutorType executor;

// Enable intra-process to guarantee deterministic and synchronous delivery of the message / event
auto node_options = rclcpp::NodeOptions().use_intra_process_comms(true);
auto node = std::make_shared<rclcpp::Node>("test_node", node_options);

auto callback_group = node->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive,
false);

// Add callback group to the executor before creating the entities
executor.add_callback_group(callback_group, node->get_node_base_interface());

// Create entities, this will produce a notifier waitable event, telling the executor to refresh
// the entities collection
auto publisher = node->create_publisher<test_msgs::msg::Empty>("test_topic", rclcpp::QoS(10));
size_t callback_count = 0;
auto callback = [&callback_count](test_msgs::msg::Empty::ConstSharedPtr) {callback_count++;};
rclcpp::SubscriptionOptions sub_options;
sub_options.callback_group = callback_group;
auto subscription =
node->create_subscription<test_msgs::msg::Empty>(
"test_topic", rclcpp::QoS(10), std::move(callback), sub_options);

ASSERT_EQ(callback_count, 0u);

// Publish a message so that the new entities (i.e. the subscriber) already have work to do
publisher->publish(test_msgs::msg::Empty());

// We need to select a duration that is greater than
// the time taken to refresh the entities collection and rebuild the waitset.
// spin-all is expected to process the notifier waitable event, rebuild the collection,
// and then collect more work, finding the subscription message event.
// This duration has been selected empirically.
executor.spin_all(std::chrono::milliseconds(500));

// Verify that the callback is called as part of the spin above
EXPECT_EQ(callback_count, 1u);
}

0 comments on commit 77ddcd1

Please sign in to comment.