Skip to content

Commit

Permalink
Merge pull request ros2#28 from alsora/asoragna/merge-conflicts
Browse files Browse the repository at this point in the history
Asoragna/merge conflicts
  • Loading branch information
iRobot ROS authored Oct 21, 2020
2 parents 35741d3 + b7174da commit 292fe84
Show file tree
Hide file tree
Showing 17 changed files with 97 additions and 28 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -64,9 +64,14 @@ class StaticExecutorEntitiesCollector final
void
init(
rcl_wait_set_t * p_wait_set,
rclcpp::memory_strategy::MemoryStrategy::SharedPtr & memory_strategy,
rclcpp::memory_strategy::MemoryStrategy::SharedPtr memory_strategy,
rcl_guard_condition_t * executor_guard_condition);

/// Finalize StaticExecutorEntitiesCollector to clear resources
RCLCPP_PUBLIC
void
fini();

RCLCPP_PUBLIC
void
execute() override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -193,6 +193,7 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor
std::chrono::nanoseconds timeout_left = timeout_ns;

entities_collector_->init(&wait_set_, memory_strategy_, &interrupt_guard_condition_);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());

while (rclcpp::ok(this->context_)) {
// Do one set of work.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ StaticExecutorEntitiesCollector::~StaticExecutorEntitiesCollector()
void
StaticExecutorEntitiesCollector::init(
rcl_wait_set_t * p_wait_set,
rclcpp::memory_strategy::MemoryStrategy::SharedPtr & memory_strategy,
rclcpp::memory_strategy::MemoryStrategy::SharedPtr memory_strategy,
rcl_guard_condition_t * executor_guard_condition)
{
// Empty initialize executable list
Expand All @@ -80,6 +80,13 @@ StaticExecutorEntitiesCollector::init(
execute();
}

void
StaticExecutorEntitiesCollector::fini()
{
memory_strategy_->clear_handles();
exec_list_.clear();
}

void
StaticExecutorEntitiesCollector::execute()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ StaticSingleThreadedExecutor::spin()
// Set memory_strategy_ and exec_list_ based on weak_nodes_
// Prepare wait_set_ based on memory_strategy_
entities_collector_->init(&wait_set_, memory_strategy_, &interrupt_guard_condition_);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());

while (rclcpp::ok(this->context_) && spinning.load()) {
// Refresh wait set and wait for work
Expand Down
16 changes: 10 additions & 6 deletions rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,9 @@ if(TARGET test_create_subscription)
"test_msgs"
)
endif()
ament_add_gtest(test_add_callback_groups_to_executor rclcpp/test_add_callback_groups_to_executor.cpp)
ament_add_gtest(test_add_callback_groups_to_executor
rclcpp/test_add_callback_groups_to_executor.cpp
TIMEOUT 120)
if(TARGET test_add_callback_groups_to_executor)
target_link_libraries(test_add_callback_groups_to_executor ${PROJECT_NAME})
ament_target_dependencies(test_add_callback_groups_to_executor
Expand Down Expand Up @@ -214,7 +216,8 @@ if(TARGET test_node_interfaces__node_clock)
target_link_libraries(test_node_interfaces__node_clock ${PROJECT_NAME})
endif()
ament_add_gtest(test_node_interfaces__node_graph
rclcpp/node_interfaces/test_node_graph.cpp)
rclcpp/node_interfaces/test_node_graph.cpp
TIMEOUT 120)
if(TARGET test_node_interfaces__node_graph)
ament_target_dependencies(
test_node_interfaces__node_graph
Expand Down Expand Up @@ -329,7 +332,7 @@ ament_add_gtest(test_parameter_map rclcpp/test_parameter_map.cpp)
if(TARGET test_parameter_map)
target_link_libraries(test_parameter_map ${PROJECT_NAME})
endif()
ament_add_gtest(test_publisher rclcpp/test_publisher.cpp)
ament_add_gtest(test_publisher rclcpp/test_publisher.cpp TIMEOUT 120)
if(TARGET test_publisher)
ament_target_dependencies(test_publisher
"rcl"
Expand Down Expand Up @@ -412,7 +415,8 @@ if(TARGET test_service)
)
target_link_libraries(test_service ${PROJECT_NAME} mimick)
endif()
ament_add_gtest(test_subscription rclcpp/test_subscription.cpp)
# Creating and destroying nodes is slow with Connext, so this needs larger timeout.
ament_add_gtest(test_subscription rclcpp/test_subscription.cpp TIMEOUT 120)
if(TARGET test_subscription)
ament_target_dependencies(test_subscription
"rcl_interfaces"
Expand Down Expand Up @@ -583,7 +587,7 @@ if(TARGET test_multi_threaded_executor)
endif()

ament_add_gtest(test_static_executor_entities_collector rclcpp/executors/test_static_executor_entities_collector.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}")
APPEND_LIBRARY_DIRS "${append_library_dirs}" TIMEOUT 120)
if(TARGET test_static_executor_entities_collector)
ament_target_dependencies(test_static_executor_entities_collector
"rcl"
Expand Down Expand Up @@ -673,7 +677,7 @@ endif()

ament_add_gtest(test_executor rclcpp/test_executor.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}"
)
TIMEOUT 120)
if(TARGET test_executor)
ament_target_dependencies(test_executor "rcl")
target_link_libraries(test_executor ${PROJECT_NAME} mimick)
Expand Down
11 changes: 8 additions & 3 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,9 +120,9 @@ class ExecutorTypeNames
}
};

// TYPED_TEST_CASE is deprecated as of gtest 1.9, use TYPED_TEST_SUITE when gtest dependency
// TYPED_TEST_SUITE is deprecated as of gtest 1.9, use TYPED_TEST_SUITE when gtest dependency
// is updated.
TYPED_TEST_CASE(TestExecutors, ExecutorTypes, ExecutorTypeNames);
TYPED_TEST_SUITE(TestExecutors, ExecutorTypes, ExecutorTypeNames);

// StaticSingleThreadedExecutor is not included in these tests for now, due to:
// https://github.com/ros2/rclcpp/issues/1219
Expand All @@ -131,7 +131,7 @@ using StandardExecutors =
rclcpp::executors::SingleThreadedExecutor,
rclcpp::executors::MultiThreadedExecutor,
rclcpp::executors::EventsExecutor>;
TYPED_TEST_CASE(TestExecutorsStable, StandardExecutors, ExecutorTypeNames);
TYPED_TEST_SUITE(TestExecutorsStable, StandardExecutors, ExecutorTypeNames);

// Make sure that executors detach from nodes when destructing
TYPED_TEST(TestExecutors, detachOnDestruction) {
Expand Down Expand Up @@ -421,6 +421,11 @@ class TestWaitable : public rclcpp::Waitable
if (on_destruction_callback_) {
on_destruction_callback_(this);
}

rcl_ret_t ret = rcl_guard_condition_fini(&gc_);
if (RCL_RET_OK != ret) {
fprintf(stderr, "failed to call rcl_guard_condition_fini\n");
}
}

bool
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +170,7 @@ TEST_F(TestStaticExecutorEntitiesCollector, add_remove_basic_node) {
rcl_guard_condition_t rcl_guard_condition = guard_condition.get_rcl_guard_condition();

entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());
EXPECT_EQ(
expected_number_of_entities->subscriptions,
entities_collector_->get_number_of_subscriptions());
Expand Down Expand Up @@ -217,6 +218,7 @@ TEST_F(TestStaticExecutorEntitiesCollector, add_remove_node_out_of_scope) {

// Expect weak_node pointers to be cleaned up and used
entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());
EXPECT_EQ(0u, entities_collector_->get_number_of_subscriptions());
EXPECT_EQ(0u, entities_collector_->get_number_of_timers());
EXPECT_EQ(0u, entities_collector_->get_number_of_services());
Expand Down Expand Up @@ -278,6 +280,7 @@ TEST_F(TestStaticExecutorEntitiesCollector, add_remove_node_with_entities) {
rcl_guard_condition_t rcl_guard_condition = guard_condition.get_rcl_guard_condition();

entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());

EXPECT_EQ(
1u + expected_number_of_entities->subscriptions,
Expand Down Expand Up @@ -356,6 +359,7 @@ TEST_F(TestStaticExecutorEntitiesCollector, prepare_wait_set_rcl_wait_set_clear_
rcl_guard_condition_t rcl_guard_condition = guard_condition.get_rcl_guard_condition();

entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());

{
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_wait_set_clear, RCL_RET_ERROR);
Expand All @@ -365,7 +369,6 @@ TEST_F(TestStaticExecutorEntitiesCollector, prepare_wait_set_rcl_wait_set_clear_
}

EXPECT_TRUE(entities_collector_->remove_node(node->get_node_base_interface()));
entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
}

TEST_F(TestStaticExecutorEntitiesCollector, prepare_wait_set_rcl_wait_set_resize_error) {
Expand All @@ -386,6 +389,7 @@ TEST_F(TestStaticExecutorEntitiesCollector, prepare_wait_set_rcl_wait_set_resize
rcl_guard_condition_t rcl_guard_condition = guard_condition.get_rcl_guard_condition();

entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());

{
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_wait_set_resize, RCL_RET_ERROR);
Expand All @@ -395,7 +399,6 @@ TEST_F(TestStaticExecutorEntitiesCollector, prepare_wait_set_rcl_wait_set_resize
}

EXPECT_TRUE(entities_collector_->remove_node(node->get_node_base_interface()));
entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
}

TEST_F(TestStaticExecutorEntitiesCollector, refresh_wait_set_not_initialized) {
Expand Down Expand Up @@ -423,6 +426,7 @@ TEST_F(TestStaticExecutorEntitiesCollector, refresh_wait_set_rcl_wait_failed) {
rcl_guard_condition_t rcl_guard_condition = guard_condition.get_rcl_guard_condition();

entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());

{
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_wait, RCL_RET_ERROR);
Expand All @@ -432,7 +436,6 @@ TEST_F(TestStaticExecutorEntitiesCollector, refresh_wait_set_rcl_wait_failed) {
}

EXPECT_TRUE(entities_collector_->remove_node(node->get_node_base_interface()));
entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
}

TEST_F(TestStaticExecutorEntitiesCollector, refresh_wait_set_add_handles_to_wait_set_failed) {
Expand Down Expand Up @@ -472,6 +475,7 @@ TEST_F(TestStaticExecutorEntitiesCollector, refresh_wait_set_add_handles_to_wait
rcl_guard_condition_t rcl_guard_condition = guard_condition.get_rcl_guard_condition();

entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());

{
auto mock = mocking_utils::patch_and_return(
Expand All @@ -483,7 +487,6 @@ TEST_F(TestStaticExecutorEntitiesCollector, refresh_wait_set_add_handles_to_wait
}

entities_collector_->remove_node(node->get_node_base_interface());
entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
}

TEST_F(TestStaticExecutorEntitiesCollector, add_to_wait_set_nullptr) {
Expand All @@ -504,14 +507,14 @@ TEST_F(TestStaticExecutorEntitiesCollector, add_to_wait_set_nullptr) {
rcl_guard_condition_t rcl_guard_condition = guard_condition.get_rcl_guard_condition();

entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());

RCLCPP_EXPECT_THROW_EQ(
entities_collector_->add_to_wait_set(nullptr),
std::runtime_error("Executor waitable: couldn't add guard condition to wait set"));
rcl_reset_error();

EXPECT_TRUE(entities_collector_->remove_node(node->get_node_base_interface()));
entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
}

TEST_F(TestStaticExecutorEntitiesCollector, fill_memory_strategy_invalid_group) {
Expand Down Expand Up @@ -540,10 +543,10 @@ TEST_F(TestStaticExecutorEntitiesCollector, fill_memory_strategy_invalid_group)
cb_group.reset();

entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());
ASSERT_EQ(entities_collector_->get_all_callback_groups().size(), 1u);

EXPECT_TRUE(entities_collector_->remove_node(node->get_node_base_interface()));
entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
}

TEST_F(TestStaticExecutorEntitiesCollector, remove_callback_group_after_node) {
Expand Down Expand Up @@ -610,10 +613,10 @@ TEST_F(
rcl_guard_condition_t rcl_guard_condition = guard_condition.get_rcl_guard_condition();

entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());

cb_group->get_associated_with_executor_atomic().exchange(false);
entities_collector_->execute();

EXPECT_TRUE(entities_collector_->remove_node(node->get_node_base_interface()));
entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
}
6 changes: 5 additions & 1 deletion rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,10 @@
#include "rclcpp/executor.hpp"
#include "rclcpp/rclcpp.hpp"

// Note: This is a long running test with rmw_connext_cpp, if you change this file, please check
// that this test can complete fully, or adjust the timeout as necessary.
// See https://github.com/ros2/rmw_connext/issues/325 for resolution]

using namespace std::chrono_literals;

template<typename T>
Expand Down Expand Up @@ -80,7 +84,7 @@ class ExecutorTypeNames
}
};

TYPED_TEST_CASE(TestAddCallbackGroupsToExecutor, ExecutorTypes, ExecutorTypeNames);
TYPED_TEST_SUITE(TestAddCallbackGroupsToExecutor, ExecutorTypes, ExecutorTypeNames);

/*
* Test adding callback groups.
Expand Down
21 changes: 18 additions & 3 deletions rclcpp/test/rclcpp/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,10 @@

#include "test_msgs/msg/empty.hpp"

// Note: This is a long running test with rmw_connext_cpp, if you change this file, please check
// that this test can complete fully, or adjust the timeout as necessary.
// See https://github.com/ros2/rmw_connext/issues/325 for resolution

class TestPublisher : public ::testing::Test
{
public:
Expand Down Expand Up @@ -180,7 +184,7 @@ static std::vector<TestParameters> invalid_qos_profiles()
return parameters;
}

INSTANTIATE_TEST_CASE_P(
INSTANTIATE_TEST_SUITE_P(
TestPublisherThrows, TestPublisherInvalidIntraprocessQos,
::testing::ValuesIn(invalid_qos_profiles()),
::testing::PrintToStringParamName());
Expand Down Expand Up @@ -274,6 +278,9 @@ TEST_F(TestPublisher, serialized_message_publish) {
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", 10, options);

rclcpp::SerializedMessage serialized_msg;
// Mock successful rcl publish because the serialized_msg above is poorly formed
auto mock = mocking_utils::patch_and_return(
"self", rcl_publish_serialized_message, RCL_RET_OK);
EXPECT_NO_THROW(publisher->publish(serialized_msg));

EXPECT_NO_THROW(publisher->publish(serialized_msg.get_rcl_serialized_message()));
Expand Down Expand Up @@ -411,14 +418,22 @@ TEST_F(TestPublisher, inter_process_publish_failures) {
EXPECT_THROW(publisher->publish(msg), rclcpp::exceptions::RCLError);
}

rclcpp::SerializedMessage serialized_msg;
EXPECT_NO_THROW(publisher->publish(serialized_msg));
{
// Using 'self' instead of 'lib:rclcpp' because `rcl_publish_serialized_message` is entirely
// defined in a header. Also, this one requires mocking because the serialized_msg is poorly
// formed and this just tests rclcpp functionality.
auto mock = mocking_utils::patch_and_return(
"self", rcl_publish_serialized_message, RCL_RET_OK);
rclcpp::SerializedMessage serialized_msg;
EXPECT_NO_THROW(publisher->publish(serialized_msg));
}

{
// Using 'self' instead of 'lib:rclcpp' because `rcl_publish_serialized_message` is entirely
// defined in a header
auto mock = mocking_utils::patch_and_return(
"self", rcl_publish_serialized_message, RCL_RET_ERROR);
rclcpp::SerializedMessage serialized_msg;
EXPECT_THROW(publisher->publish(serialized_msg), rclcpp::exceptions::RCLError);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@ using AllTestDescriptions = ::testing::Types<
TwoSubscriptionsInTwoContextsWithIntraprocessComm,
TwoSubscriptionsInTwoContextsWithoutIntraprocessComm
>;
TYPED_TEST_CASE(TestPublisherSubscriptionCount, AllTestDescriptions, PrintTestDescription);
TYPED_TEST_SUITE(TestPublisherSubscriptionCount, AllTestDescriptions, PrintTestDescription);


using test_msgs::msg::Empty;
Expand Down
6 changes: 5 additions & 1 deletion rclcpp/test/rclcpp/test_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,10 @@

#include "test_msgs/msg/empty.hpp"

// Note: This is a long running test with rmw_connext_cpp, if you change this file, please check
// that this test can complete fully, or adjust the timeout as necessary.
// See https://github.com/ros2/rmw_connext/issues/325 for resolution

using namespace std::chrono_literals;

class TestSubscription : public ::testing::Test
Expand Down Expand Up @@ -502,7 +506,7 @@ static std::vector<TestParameters> invalid_qos_profiles()
return parameters;
}

INSTANTIATE_TEST_CASE_P(
INSTANTIATE_TEST_SUITE_P(
TestSubscriptionThrows, TestSubscriptionInvalidIntraprocessQos,
::testing::ValuesIn(invalid_qos_profiles()),
::testing::PrintToStringParamName());
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ struct TwoContextsPerTest
};

using AllTestDescriptions = ::testing::Types<OneContextPerTest, TwoContextsPerTest>;
TYPED_TEST_CASE(TestSubscriptionPublisherCount, AllTestDescriptions, PrintTestDescription);
TYPED_TEST_SUITE(TestSubscriptionPublisherCount, AllTestDescriptions, PrintTestDescription);


using test_msgs::msg::Empty;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_action/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ if(BUILD_TESTING)
)
endif()

ament_add_gtest(test_server test/test_server.cpp)
ament_add_gtest(test_server test/test_server.cpp TIMEOUT 180)
if(TARGET test_server)
ament_target_dependencies(test_server
"rcutils"
Expand Down
Loading

0 comments on commit 292fe84

Please sign in to comment.