diff --git a/rcl/package.xml b/rcl/package.xml index 82d790e7c..b2295960b 100644 --- a/rcl/package.xml +++ b/rcl/package.xml @@ -34,9 +34,9 @@ rmw rmw_implementation_cmake launch - example_interfaces osrf_testing_tools_cpp std_msgs + test_msgs ament_cmake diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 6c84511d6..c76a14b5c 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -1,8 +1,8 @@ find_package(ament_cmake_gtest REQUIRED) find_package(ament_cmake_pytest REQUIRED) -find_package(example_interfaces REQUIRED) find_package(std_msgs REQUIRED) +find_package(test_msgs REQUIRED) find_package(rmw_implementation_cmake REQUIRED) @@ -38,7 +38,7 @@ function(test_target_function) ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} - AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" + AMENT_DEPENDENCIES ${rmw_implementation} "test_msgs" ) rcl_add_custom_gtest(test_time${target_suffix} @@ -99,7 +99,7 @@ function(test_target_function) ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} - AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" "std_msgs" + AMENT_DEPENDENCIES ${rmw_implementation} "std_msgs" "test_msgs" ${SKIP_TEST} ) @@ -142,7 +142,7 @@ function(test_target_function) ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} - AMENT_DEPENDENCIES "std_msgs" "example_interfaces" + AMENT_DEPENDENCIES "std_msgs" "test_msgs" ) rcl_add_custom_gtest(test_guard_condition${target_suffix} @@ -169,7 +169,7 @@ function(test_target_function) ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} - AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" + AMENT_DEPENDENCIES ${rmw_implementation} "test_msgs" ) rcl_add_custom_gtest(test_subscription${target_suffix} @@ -196,7 +196,7 @@ function(test_target_function) ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} - AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" + AMENT_DEPENDENCIES ${rmw_implementation} "test_msgs" ) # Launch tests @@ -205,14 +205,14 @@ function(test_target_function) SRCS rcl/service_fixture.cpp INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} LIBRARIES ${PROJECT_NAME} - AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" + AMENT_DEPENDENCIES ${rmw_implementation} "test_msgs" ) rcl_add_custom_executable(client_fixture${target_suffix} SRCS rcl/client_fixture.cpp INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} LIBRARIES ${PROJECT_NAME} - AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" + AMENT_DEPENDENCIES ${rmw_implementation} "test_msgs" ) rcl_add_custom_launch_test(test_services diff --git a/rcl/test/rcl/client_fixture.cpp b/rcl/test/rcl/client_fixture.cpp index 834df0cfb..992f03917 100644 --- a/rcl/test/rcl/client_fixture.cpp +++ b/rcl/test/rcl/client_fixture.cpp @@ -21,7 +21,7 @@ #include "rcl/client.h" #include "rcl/rcl.h" -#include "example_interfaces/srv/add_two_ints.h" +#include "test_msgs/srv/primitives.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" @@ -130,12 +130,12 @@ int main(int argc, char ** argv) }); const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); - const char * topic = "add_two_ints"; + test_msgs, Primitives); + const char * service_name = "primitives"; rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_options_t client_options = rcl_client_get_default_options(); - rcl_ret_t ret = rcl_client_init(&client, &node, ts, topic, &client_options); + rcl_ret_t ret = rcl_client_init(&client, &node, ts, service_name, &client_options); if (ret != RCL_RET_OK) { RCUTILS_LOG_ERROR_NAMED( ROS_PACKAGE_NAME, "Error in client init: %s", rcl_get_error_string_safe()) @@ -157,10 +157,10 @@ int main(int argc, char ** argv) } // Initialize a request. - example_interfaces__srv__AddTwoInts_Request client_request; - example_interfaces__srv__AddTwoInts_Request__init(&client_request); - client_request.a = 1; - client_request.b = 2; + test_msgs__srv__Primitives_Request client_request; + test_msgs__srv__Primitives_Request__init(&client_request); + client_request.uint8_value = 1; + client_request.uint32_value = 2; int64_t sequence_number; if (rcl_send_request(&client, &client_request, &sequence_number)) { @@ -174,11 +174,11 @@ int main(int argc, char ** argv) return -1; } - example_interfaces__srv__AddTwoInts_Request__fini(&client_request); + test_msgs__srv__Primitives_Request__fini(&client_request); // Initialize the response owned by the client and take the response. - example_interfaces__srv__AddTwoInts_Response client_response; - example_interfaces__srv__AddTwoInts_Response__init(&client_response); + test_msgs__srv__Primitives_Response client_response; + test_msgs__srv__Primitives_Response__init(&client_response); if (!wait_for_client_to_be_ready(&client, 1000, 100)) { RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Client never became ready") @@ -191,7 +191,7 @@ int main(int argc, char ** argv) return -1; } - example_interfaces__srv__AddTwoInts_Response__fini(&client_response); + test_msgs__srv__Primitives_Response__fini(&client_response); } return main_ret; diff --git a/rcl/test/rcl/service_fixture.cpp b/rcl/test/rcl/service_fixture.cpp index afd132de7..db16e77a4 100644 --- a/rcl/test/rcl/service_fixture.cpp +++ b/rcl/test/rcl/service_fixture.cpp @@ -22,7 +22,7 @@ #include "rcl/rcl.h" -#include "example_interfaces/srv/add_two_ints.h" +#include "test_msgs/srv/primitives.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" @@ -103,12 +103,12 @@ int main(int argc, char ** argv) }); const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); - const char * topic = "add_two_ints"; + test_msgs, Primitives); + const char * service_name = "primitives"; rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_options_t service_options = rcl_service_get_default_options(); - rcl_ret_t ret = rcl_service_init(&service, &node, ts, topic, &service_options); + rcl_ret_t ret = rcl_service_init(&service, &node, ts, service_name, &service_options); if (ret != RCL_RET_OK) { RCUTILS_LOG_ERROR_NAMED( ROS_PACKAGE_NAME, "Error in service init: %s", rcl_get_error_string_safe()) @@ -124,10 +124,10 @@ int main(int argc, char ** argv) }); // Initialize a response. - example_interfaces__srv__AddTwoInts_Response service_response; - example_interfaces__srv__AddTwoInts_Response__init(&service_response); + test_msgs__srv__Primitives_Response service_response; + test_msgs__srv__Primitives_Response__init(&service_response); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - example_interfaces__srv__AddTwoInts_Response__fini(&service_response); + test_msgs__srv__Primitives_Response__fini(&service_response); }); // Block until a client request comes in. @@ -138,10 +138,10 @@ int main(int argc, char ** argv) } // Take the pending request. - example_interfaces__srv__AddTwoInts_Request service_request; - example_interfaces__srv__AddTwoInts_Request__init(&service_request); + test_msgs__srv__Primitives_Request service_request; + test_msgs__srv__Primitives_Request__init(&service_request); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - example_interfaces__srv__AddTwoInts_Request__fini(&service_request); + test_msgs__srv__Primitives_Request__fini(&service_request); }); rmw_request_id_t header; // TODO(jacquelinekay) May have to check for timeout error codes @@ -152,7 +152,7 @@ int main(int argc, char ** argv) } // Sum the request and send the response. - service_response.sum = service_request.a + service_request.b; + service_response.uint64_value = service_request.uint8_value + service_request.uint32_value; if (rcl_send_response(&service, &header, &service_response) != RCL_RET_OK) { RCUTILS_LOG_ERROR_NAMED( ROS_PACKAGE_NAME, "Error in send_response: %s", rcl_get_error_string_safe()) diff --git a/rcl/test/rcl/test_client.cpp b/rcl/test/rcl/test_client.cpp index 599fd9fcb..f890bcac2 100644 --- a/rcl/test/rcl/test_client.cpp +++ b/rcl/test/rcl/test_client.cpp @@ -18,8 +18,8 @@ #include "rcl/rcl.h" -#include "example_interfaces/srv/add_two_ints.h" #include "rosidl_generator_c/string_functions.h" +#include "test_msgs/srv/primitives.h" #include "./failing_allocator_functions.hpp" #include "osrf_testing_tools_cpp/scope_exit.hpp" @@ -64,7 +64,7 @@ TEST_F(TestClientFixture, test_client_nominal) { rcl_client_options_t client_options = rcl_client_get_default_options(); const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); + test_msgs, Primitives); ret = rcl_client_init(&client, this->node_ptr, ts, topic_name, &client_options); // Check the return code of initialization and that the service name matches what's expected @@ -77,10 +77,10 @@ TEST_F(TestClientFixture, test_client_nominal) { }); // Initialize the client request. - example_interfaces__srv__AddTwoInts_Request req; - example_interfaces__srv__AddTwoInts_Request__init(&req); - req.a = 1; - req.b = 2; + test_msgs__srv__Primitives_Request req; + test_msgs__srv__Primitives_Request__init(&req); + req.uint8_value = 1; + req.uint32_value = 2; // Check that there were no errors while sending the request. int64_t sequence_number = 0; @@ -98,7 +98,7 @@ TEST_F(TestClientFixture, test_client_init_fini) { rcl_client_t client; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); + test_msgs, Primitives); const char * topic_name = "chatter"; rcl_client_options_t default_client_options = rcl_client_get_default_options(); diff --git a/rcl/test/rcl/test_graph.cpp b/rcl/test/rcl/test_graph.cpp index a10baf0f6..c8aaa8538 100644 --- a/rcl/test/rcl/test_graph.cpp +++ b/rcl/test/rcl/test_graph.cpp @@ -33,7 +33,7 @@ #include "rcutils/logging_macros.h" #include "std_msgs/msg/string.h" -#include "example_interfaces/srv/add_two_ints.h" +#include "test_msgs/srv/primitives.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" @@ -469,7 +469,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_ rcl_ret_t ret; // First create a client which will be used to call the function. rcl_client_t client = rcl_get_zero_initialized_client(); - auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts); + auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, Primitives); const char * service_name = "/service_test_rcl_service_server_is_available"; rcl_client_options_t client_options = rcl_client_get_default_options(); ret = rcl_client_init(&client, this->node_ptr, ts, service_name, &client_options); diff --git a/rcl/test/rcl/test_remap_integration.cpp b/rcl/test/rcl/test_remap_integration.cpp index fa9c3ce36..6fc44bce7 100644 --- a/rcl/test/rcl/test_remap_integration.cpp +++ b/rcl/test/rcl/test_remap_integration.cpp @@ -14,11 +14,12 @@ #include -#include "example_interfaces/srv/add_two_ints.h" #include "rcl/rcl.h" #include "rcl/remap.h" #include "rcl/error_handling.h" + #include "std_msgs/msg/int64.h" +#include "test_msgs/srv/primitives.h" #include "./arg_macros.hpp" @@ -81,7 +82,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g } { // Client service name gets remapped const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); + test_msgs, Primitives); rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_t client = rcl_get_zero_initialized_client(); rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options); @@ -91,7 +92,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g } { // Server service name gets remapped const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); + test_msgs, Primitives); rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_t service = rcl_get_zero_initialized_service(); rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options); @@ -147,7 +148,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global } { // Client service name does not get remapped const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); + test_msgs, Primitives); rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_t client = rcl_get_zero_initialized_client(); rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options); @@ -157,7 +158,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global } { // Server service name does not get remapped const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); + test_msgs, Primitives); rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_t service = rcl_get_zero_initialized_service(); rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options); @@ -214,7 +215,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b } { // Client service name const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); + test_msgs, Primitives); rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_t client = rcl_get_zero_initialized_client(); rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options); @@ -224,7 +225,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b } { // Server service name const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); + test_msgs, Primitives); rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_t service = rcl_get_zero_initialized_service(); rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options); @@ -266,7 +267,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ } { // Client service name const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); + test_msgs, Primitives); rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_t client = rcl_get_zero_initialized_client(); rcl_ret_t ret = rcl_client_init(&client, &node, ts, "bar", &client_options); @@ -276,7 +277,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ } { // Server service name const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); + test_msgs, Primitives); rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_t service = rcl_get_zero_initialized_service(); rcl_ret_t ret = rcl_service_init(&service, &node, ts, "bar", &service_options); diff --git a/rcl/test/rcl/test_service.cpp b/rcl/test/rcl/test_service.cpp index 6ca020e22..55b47398c 100644 --- a/rcl/test/rcl/test_service.cpp +++ b/rcl/test/rcl/test_service.cpp @@ -22,7 +22,7 @@ #include "rcl/rcl.h" -#include "example_interfaces/srv/add_two_ints.h" +#include "test_msgs/srv/primitives.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" @@ -102,9 +102,9 @@ wait_for_service_to_be_ready( TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) { rcl_ret_t ret; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - example_interfaces, AddTwoInts); - const char * topic = "add_two_ints"; - const char * expected_topic = "/add_two_ints"; + test_msgs, Primitives); + const char * topic = "primitives"; + const char * expected_topic = "/primitives"; rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_options_t service_options = rcl_service_get_default_options(); @@ -149,14 +149,14 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) std::this_thread::sleep_for(std::chrono::milliseconds(1000)); // Initialize a request. - example_interfaces__srv__AddTwoInts_Request client_request; - example_interfaces__srv__AddTwoInts_Request__init(&client_request); - client_request.a = 1; - client_request.b = 2; + test_msgs__srv__Primitives_Request client_request; + test_msgs__srv__Primitives_Request__init(&client_request); + client_request.uint8_value = 1; + client_request.uint32_value = 2; int64_t sequence_number; ret = rcl_send_request(&client, &client_request, &sequence_number); EXPECT_EQ(sequence_number, 1); - example_interfaces__srv__AddTwoInts_Request__fini(&client_request); + test_msgs__srv__Primitives_Request__fini(&client_request); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); bool success; @@ -167,35 +167,35 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) // test take_request/send_response in a single-threaded, deterministic execution. { // Initialize a response. - example_interfaces__srv__AddTwoInts_Response service_response; - example_interfaces__srv__AddTwoInts_Response__init(&service_response); + test_msgs__srv__Primitives_Response service_response; + test_msgs__srv__Primitives_Response__init(&service_response); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - example_interfaces__srv__AddTwoInts_Response__fini(&service_response); + test_msgs__srv__Primitives_Response__fini(&service_response); }); // Initialize a separate instance of the request and take the pending request. - example_interfaces__srv__AddTwoInts_Request service_request; - example_interfaces__srv__AddTwoInts_Request__init(&service_request); + test_msgs__srv__Primitives_Request service_request; + test_msgs__srv__Primitives_Request__init(&service_request); rmw_request_id_t header; ret = rcl_take_request(&service, &header, &service_request); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - EXPECT_EQ(1, service_request.a); - EXPECT_EQ(2, service_request.b); + EXPECT_EQ(1, service_request.uint8_value); + EXPECT_EQ(2UL, service_request.uint32_value); // Simulate a response callback by summing the request and send the response.. - service_response.sum = service_request.a + service_request.b; + service_response.uint64_value = service_request.uint8_value + service_request.uint32_value; ret = rcl_send_response(&service, &header, &service_response); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); } wait_for_service_to_be_ready(&service, 10, 100, success); // Initialize the response owned by the client and take the response. - example_interfaces__srv__AddTwoInts_Response client_response; - example_interfaces__srv__AddTwoInts_Response__init(&client_response); + test_msgs__srv__Primitives_Response client_response; + test_msgs__srv__Primitives_Response__init(&client_response); rmw_request_id_t header; ret = rcl_take_response(&client, &header, &client_response); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - EXPECT_EQ(client_response.sum, 3); + EXPECT_EQ(client_response.uint64_value, 3ULL); EXPECT_EQ(header.sequence_number, 1); } diff --git a/rcl/test/test_namespace.cpp b/rcl/test/test_namespace.cpp index ad5479819..d67b33357 100644 --- a/rcl/test/test_namespace.cpp +++ b/rcl/test/test_namespace.cpp @@ -22,8 +22,8 @@ #include "rcl/rcl.h" #include "rcl/graph.h" -#include "example_interfaces/srv/add_two_ints.h" #include "rosidl_generator_c/string_functions.h" +#include "test_msgs/srv/primitives.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" @@ -61,7 +61,7 @@ class TestNamespaceFixture : public ::testing::Test */ TEST_F(TestNamespaceFixture, test_client_server) { rcl_ret_t ret; - auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts); + auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, Primitives); const char * service_name = "/my/namespace/test_namespace_client_server"; const char * unmatched_client_name = "/your/namespace/test_namespace_client_server"; const char * matched_client_name = "/my/namespace/test_namespace_client_server";