Skip to content

Commit

Permalink
Stop compiling rcl_action tests multiple times. (#1165)
Browse files Browse the repository at this point in the history
We don't need to compile the tests once for each RMW;
we can just compile it once and then use the RMW_IMPLEMENTATION
environment variable to run the tests on the different RMWs.
This speeds up compilation.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Jul 2, 2024
1 parent 3e7ce76 commit 250d820
Show file tree
Hide file tree
Showing 4 changed files with 81 additions and 95 deletions.
83 changes: 46 additions & 37 deletions rcl_action/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -102,47 +102,56 @@ if(BUILD_TESTING)
target_compile_definitions(test_action_client PUBLIC RCUTILS_ENABLE_FAULT_INJECTION)
endif()

# get the rmw implementations ahead of time
find_package(rmw_implementation_cmake REQUIRED)
get_available_rmw_implementations(rmw_implementations)
foreach(rmw_implementation ${rmw_implementations})
find_package("${rmw_implementation}" REQUIRED)
endforeach()

function(custom_test_c target)
ament_add_gtest(
"${target}${target_suffix}" ${ARGN}
TIMEOUT 180
ENV
RCL_ASSERT_RMW_ID_MATCHES=${rmw_implementation}
RMW_IMPLEMENTATION=${rmw_implementation}
ament_add_gtest_executable(test_action_communication test/rcl_action/test_action_communication.cpp)
target_link_libraries(test_action_communication
${PROJECT_NAME}
${action_msgs_TARGETS}
osrf_testing_tools_cpp::memory_tools
rcl::rcl
rosidl_runtime_c::rosidl_runtime_c
${test_msgs_TARGETS})

ament_add_gtest_executable(test_action_interaction test/rcl_action/test_action_interaction.cpp)
target_link_libraries(test_action_interaction
${PROJECT_NAME}
${action_msgs_TARGETS}
osrf_testing_tools_cpp::memory_tools
rcl::rcl
rosidl_runtime_c::rosidl_runtime_c
${test_msgs_TARGETS})

ament_add_gtest_executable(test_graph test/rcl_action/test_graph.cpp)
target_compile_definitions(test_graph PUBLIC RCUTILS_ENABLE_FAULT_INJECTION)
target_link_libraries(test_graph
${PROJECT_NAME}
${action_msgs_TARGETS}
osrf_testing_tools_cpp::memory_tools
rcl::rcl
rcutils::rcutils
rosidl_runtime_c::rosidl_runtime_c
${test_msgs_TARGETS})

function(test_targets)
message(STATUS "Creating tests for '${rmw_implementation}'")
set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation})

ament_add_gtest_test(test_action_communication
TEST_NAME test_action_communication${target_suffix}
ENV ${rmw_implementation_env_var}
)
if(TARGET ${target}${target_suffix})
target_compile_definitions(${target}${target_suffix}
PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}")
target_compile_definitions(${target}${target_suffix}
PUBLIC RCUTILS_ENABLE_FAULT_INJECTION)
target_link_libraries(${target}${target_suffix}
${PROJECT_NAME}
osrf_testing_tools_cpp::memory_tools
rcl::rcl
rosidl_runtime_c::rosidl_runtime_c
${test_msgs_TARGETS}
)
endif()
endfunction()

macro(targets)
custom_test_c(test_action_communication
"test/rcl_action/test_action_communication.cpp")
custom_test_c(test_action_interaction
"test/rcl_action/test_action_interaction.cpp")
ament_add_gtest_test(test_action_interaction
TEST_NAME test_action_interaction${target_suffix}
ENV ${rmw_implementation_env_var}
)

custom_test_c(test_graph
"test/rcl_action/test_graph.cpp")
endmacro()
ament_add_gtest_test(test_graph
TEST_NAME test_graph${target_suffix}
ENV ${rmw_implementation_env_var}
)
endfunction()

call_for_each_rmw_implementation(targets)
call_for_each_rmw_implementation(test_targets)

ament_add_gtest(test_action_server
test/rcl_action/test_action_server.cpp
Expand Down
41 changes: 17 additions & 24 deletions rcl_action/test/rcl_action/test_action_communication.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,16 +27,11 @@

#include "rosidl_runtime_c/primitives_sequence_functions.h"

#include "test_msgs/action/fibonacci.h"
#include "action_msgs/srv/cancel_goal.h"

#ifdef RMW_IMPLEMENTATION
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
#else
# define CLASSNAME(NAME, SUFFIX) NAME
#endif
#include "test_msgs/action/fibonacci.h"

class CLASSNAME (TestActionCommunication, RMW_IMPLEMENTATION) : public ::testing::Test
class TestActionCommunication : public ::testing::Test
{
protected:
void SetUp() override
Expand Down Expand Up @@ -182,7 +177,7 @@ class CLASSNAME (TestActionCommunication, RMW_IMPLEMENTATION) : public ::testing
bool is_result_response_ready;
}; // class TestActionCommunication

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_goal_comm)
TEST_F(TestActionCommunication, test_valid_goal_comm)
{
test_msgs__action__Fibonacci_SendGoal_Request outgoing_goal_request;
test_msgs__action__Fibonacci_SendGoal_Request incoming_goal_request;
Expand Down Expand Up @@ -288,8 +283,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_goal_c
test_msgs__action__Fibonacci_SendGoal_Response__fini(&outgoing_goal_response);
}


TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_cancel_comm)
TEST_F(TestActionCommunication, test_valid_cancel_comm)
{
action_msgs__srv__CancelGoal_Request outgoing_cancel_request;
action_msgs__srv__CancelGoal_Request incoming_cancel_request;
Expand Down Expand Up @@ -416,7 +410,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_cancel
action_msgs__srv__CancelGoal_Response__fini(&outgoing_cancel_response);
}

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result_comm)
TEST_F(TestActionCommunication, test_valid_result_comm)
{
test_msgs__action__Fibonacci_GetResult_Request outgoing_result_request;
test_msgs__action__Fibonacci_GetResult_Request incoming_result_request;
Expand Down Expand Up @@ -531,7 +525,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result
test_msgs__action__Fibonacci_GetResult_Response__fini(&outgoing_result_response);
}

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_status_comm)
TEST_F(TestActionCommunication, test_valid_status_comm)
{
action_msgs__msg__GoalStatusArray incoming_status_array;
action_msgs__msg__GoalStatusArray__init(&incoming_status_array);
Expand Down Expand Up @@ -607,7 +601,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_status
EXPECT_EQ(RCL_RET_OK, rcl_action_goal_handle_fini(goal_handle));
}

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedback_comm)
TEST_F(TestActionCommunication, test_valid_feedback_comm)
{
test_msgs__action__Fibonacci_FeedbackMessage outgoing_feedback;
test_msgs__action__Fibonacci_FeedbackMessage incoming_feedback;
Expand Down Expand Up @@ -670,7 +664,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedba
test_msgs__action__Fibonacci_FeedbackMessage__fini(&outgoing_feedback);
}

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal_request_opts)
TEST_F(TestActionCommunication, test_invalid_goal_request_opts)
{
test_msgs__action__Fibonacci_SendGoal_Request outgoing_goal_request;
test_msgs__action__Fibonacci_SendGoal_Request incoming_goal_request;
Expand Down Expand Up @@ -727,7 +721,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal
test_msgs__action__Fibonacci_SendGoal_Request__fini(&incoming_goal_request);
}

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal_response_opts)
TEST_F(TestActionCommunication, test_invalid_goal_response_opts)
{
test_msgs__action__Fibonacci_SendGoal_Response outgoing_goal_response;
test_msgs__action__Fibonacci_SendGoal_Response incoming_goal_response;
Expand Down Expand Up @@ -788,7 +782,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal
test_msgs__action__Fibonacci_SendGoal_Response__fini(&outgoing_goal_response);
}

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_cancel_request_opts)
TEST_F(TestActionCommunication, test_invalid_cancel_request_opts)
{
action_msgs__srv__CancelGoal_Request outgoing_cancel_request;
action_msgs__srv__CancelGoal_Request incoming_cancel_request;
Expand Down Expand Up @@ -846,8 +840,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_canc
action_msgs__srv__CancelGoal_Request__fini(&outgoing_cancel_request);
}


TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_cancel_response_opts)
TEST_F(TestActionCommunication, test_invalid_cancel_response_opts)
{
action_msgs__srv__CancelGoal_Response outgoing_cancel_response;
action_msgs__srv__CancelGoal_Response incoming_cancel_response;
Expand Down Expand Up @@ -910,7 +903,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_canc
action_msgs__srv__CancelGoal_Response__fini(&outgoing_cancel_response);
}

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_result_request_opts)
TEST_F(TestActionCommunication, test_invalid_result_request_opts)
{
test_msgs__action__Fibonacci_GetResult_Request outgoing_result_request;
test_msgs__action__Fibonacci_GetResult_Request incoming_result_request;
Expand Down Expand Up @@ -966,7 +959,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_resu
test_msgs__action__Fibonacci_GetResult_Request__fini(&outgoing_result_request);
}

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_result_response_opts)
TEST_F(TestActionCommunication, test_invalid_result_response_opts)
{
test_msgs__action__Fibonacci_GetResult_Response outgoing_result_response;
test_msgs__action__Fibonacci_GetResult_Response incoming_result_response;
Expand Down Expand Up @@ -1029,7 +1022,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_resu
test_msgs__action__Fibonacci_GetResult_Response__fini(&outgoing_result_response);
}

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feedback_opts)
TEST_F(TestActionCommunication, test_invalid_feedback_opts)
{
test_msgs__action__Fibonacci_FeedbackMessage outgoing_feedback;
test_msgs__action__Fibonacci_FeedbackMessage incoming_feedback;
Expand Down Expand Up @@ -1081,7 +1074,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feed
test_msgs__action__Fibonacci_FeedbackMessage__fini(&outgoing_feedback);
}

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_status_opts)
TEST_F(TestActionCommunication, test_invalid_status_opts)
{
action_msgs__msg__GoalStatusArray incoming_status_array;
action_msgs__msg__GoalStatusArray__init(&incoming_status_array);
Expand Down Expand Up @@ -1130,7 +1123,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_stat
action_msgs__msg__GoalStatusArray__fini(&incoming_status_array);
}

TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedback_comm_maybe_fail)
TEST_F(TestActionCommunication, test_valid_feedback_comm_maybe_fail)
{
test_msgs__action__Fibonacci_FeedbackMessage outgoing_feedback;
test_msgs__action__Fibonacci_FeedbackMessage incoming_feedback;
Expand Down
16 changes: 5 additions & 11 deletions rcl_action/test/rcl_action/test_action_interaction.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,16 +24,11 @@

#include "rosidl_runtime_c/primitives_sequence_functions.h"

#include "test_msgs/action/fibonacci.h"
#include "action_msgs/srv/cancel_goal.h"

#ifdef RMW_IMPLEMENTATION
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
#else
# define CLASSNAME(NAME, SUFFIX) NAME
#endif
#include "test_msgs/action/fibonacci.h"

class CLASSNAME (TestActionClientServerInteraction, RMW_IMPLEMENTATION) : public ::testing::Test
class TestActionClientServerInteraction : public ::testing::Test
{
protected:
void SetUp() override
Expand Down Expand Up @@ -204,7 +199,7 @@ class CLASSNAME (TestActionClientServerInteraction, RMW_IMPLEMENTATION) : public
// Following the goal request, the client makes an asynchronous request for the
// result. The feedback is published to the action client as it executes the goal.
// Ultimately, a result message is populated which is then used as part of the result response.
TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_interaction)
TEST_F(TestActionClientServerInteraction, test_interaction)
{
// Initialize goal request
init_test_uuid0(this->outgoing_goal_request.goal_id.uuid);
Expand Down Expand Up @@ -467,8 +462,7 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in
// This example is almost identical to the first, but this time the action client requests
// for the goal to be canceled mid-execution. Note that it is allowed to perform any shutdown
// operations after the cancel request before returning with the cancellation result.
TEST_F(
CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_interaction_with_cancel)
TEST_F(TestActionClientServerInteraction, test_interaction_with_cancel)
{
action_msgs__srv__CancelGoal_Request outgoing_cancel_request;
action_msgs__srv__CancelGoal_Request incoming_cancel_request;
Expand Down
36 changes: 13 additions & 23 deletions rcl_action/test/rcl_action/test_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,19 +30,12 @@

#include "test_msgs/action/fibonacci.h"

#ifdef RMW_IMPLEMENTATION
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
#else
# define CLASSNAME(NAME, SUFFIX) NAME
#endif

void * bad_malloc(size_t, void *)
{
return NULL;
}

class CLASSNAME (TestActionGraphFixture, RMW_IMPLEMENTATION) : public ::testing::Test
class TestActionGraphFixture : public ::testing::Test
{
public:
rcl_allocator_t allocator = rcl_get_default_allocator();
Expand Down Expand Up @@ -106,9 +99,7 @@ class CLASSNAME (TestActionGraphFixture, RMW_IMPLEMENTATION) : public ::testing:
}
};

TEST_F(
CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION),
test_action_get_client_names_and_types_by_node)
TEST_F(TestActionGraphFixture, test_action_get_client_names_and_types_by_node)
{
rcl_ret_t ret;
rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
Expand Down Expand Up @@ -168,9 +159,7 @@ TEST_F(
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}

TEST_F(
CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION),
test_action_get_server_names_and_types_by_node)
TEST_F(TestActionGraphFixture, test_action_get_server_names_and_types_by_node)
{
rcl_ret_t ret;
rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
Expand Down Expand Up @@ -221,9 +210,7 @@ TEST_F(
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}

TEST_F(
CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION),
test_action_get_names_and_types)
TEST_F(TestActionGraphFixture, test_action_get_names_and_types)
{
rcl_ret_t ret;
rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
Expand Down Expand Up @@ -268,7 +255,7 @@ typedef std::function<
* Extend the TestActionGraphFixture with a multi-node fixture for node discovery and node-graph
* perspective.
*/
class TestActionGraphMultiNodeFixture : public CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION)
class TestActionGraphMultiNodeFixture : public TestActionGraphFixture
{
public:
const char * remote_node_name = "remote_graph_node";
Expand All @@ -279,7 +266,7 @@ class TestActionGraphMultiNodeFixture : public CLASSNAME(TestActionGraphFixture,

void SetUp() override
{
CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION) ::SetUp();
TestActionGraphFixture::SetUp();

rcl_ret_t ret;
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
Expand Down Expand Up @@ -326,7 +313,7 @@ class TestActionGraphMultiNodeFixture : public CLASSNAME(TestActionGraphFixture,

void TearDown() override
{
CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION) ::TearDown();
TestActionGraphFixture::TearDown();

rcl_ret_t ret;
ret = rcl_node_fini(&this->remote_node);
Expand Down Expand Up @@ -395,7 +382,8 @@ class TestActionGraphMultiNodeFixture : public CLASSNAME(TestActionGraphFixture,
};

// Note, this test could be affected by other communication on the same ROS domain
TEST_F(TestActionGraphMultiNodeFixture, test_action_get_names_and_types) {
TEST_F(TestActionGraphMultiNodeFixture, test_action_get_names_and_types)
{
rcl_ret_t ret;
// Create an action client
rcl_action_client_t action_client = rcl_action_get_zero_initialized_client();
Expand Down Expand Up @@ -472,7 +460,8 @@ TEST_F(TestActionGraphMultiNodeFixture, test_action_get_names_and_types) {
}

// Note, this test could be affected by other communication on the same ROS domain
TEST_F(TestActionGraphMultiNodeFixture, test_action_get_server_names_and_types_by_node) {
TEST_F(TestActionGraphMultiNodeFixture, test_action_get_server_names_and_types_by_node)
{
rcl_ret_t ret;
// Create an action client
rcl_action_client_t action_client = rcl_action_get_zero_initialized_client();
Expand Down Expand Up @@ -538,7 +527,8 @@ TEST_F(TestActionGraphMultiNodeFixture, test_action_get_server_names_and_types_b
}

// Note, this test could be affected by other communication on the same ROS domain
TEST_F(TestActionGraphMultiNodeFixture, test_action_get_client_names_and_types_by_node) {
TEST_F(TestActionGraphMultiNodeFixture, test_action_get_client_names_and_types_by_node)
{
rcl_ret_t ret;
const rosidl_action_type_support_t * action_typesupport =
ROSIDL_GET_ACTION_TYPE_SUPPORT(test_msgs, Fibonacci);
Expand Down

0 comments on commit 250d820

Please sign in to comment.