diff --git a/rcl/test/rcl/client_fixture.cpp b/rcl/test/rcl/client_fixture.cpp index 42cf6405fd..6ccdabe6cb 100644 --- a/rcl/test/rcl/client_fixture.cpp +++ b/rcl/test/rcl/client_fixture.cpp @@ -22,7 +22,7 @@ #include "rcl/client.h" #include "rcl/rcl.h" -#include "test_msgs/srv/primitives.h" +#include "test_msgs/srv/basic_types.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" @@ -153,8 +153,8 @@ int main(int argc, char ** argv) }); const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - test_msgs, srv, Primitives); - const char * service_name = "primitives"; + test_msgs, srv, BasicTypes); + const char * service_name = "basic_types"; rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_options_t client_options = rcl_client_get_default_options(); @@ -180,11 +180,11 @@ int main(int argc, char ** argv) } // Initialize a request. - test_msgs__srv__Primitives_Request client_request; + test_msgs__srv__BasicTypes_Request client_request; // TODO(dirk-thomas) zero initialization necessary until // https://github.com/ros2/ros2/issues/397 is implemented - memset(&client_request, 0, sizeof(test_msgs__srv__Primitives_Request)); - test_msgs__srv__Primitives_Request__init(&client_request); + memset(&client_request, 0, sizeof(test_msgs__srv__BasicTypes_Request)); + test_msgs__srv__BasicTypes_Request__init(&client_request); client_request.uint8_value = 1; client_request.uint32_value = 2; int64_t sequence_number; @@ -200,14 +200,14 @@ int main(int argc, char ** argv) return -1; } - test_msgs__srv__Primitives_Request__fini(&client_request); + test_msgs__srv__BasicTypes_Request__fini(&client_request); // Initialize the response owned by the client and take the response. - test_msgs__srv__Primitives_Response client_response; + test_msgs__srv__BasicTypes_Response client_response; // TODO(dirk-thomas) zero initialization necessary until // https://github.com/ros2/ros2/issues/397 is implemented - memset(&client_response, 0, sizeof(test_msgs__srv__Primitives_Response)); - test_msgs__srv__Primitives_Response__init(&client_response); + memset(&client_response, 0, sizeof(test_msgs__srv__BasicTypes_Response)); + test_msgs__srv__BasicTypes_Response__init(&client_response); if (!wait_for_client_to_be_ready(&client, &context, 1000, 100)) { RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Client never became ready"); @@ -220,7 +220,7 @@ int main(int argc, char ** argv) return -1; } - test_msgs__srv__Primitives_Response__fini(&client_response); + test_msgs__srv__BasicTypes_Response__fini(&client_response); } return main_ret; diff --git a/rcl/test/rcl/service_fixture.cpp b/rcl/test/rcl/service_fixture.cpp index a1cc9ed876..6f38c0a755 100644 --- a/rcl/test/rcl/service_fixture.cpp +++ b/rcl/test/rcl/service_fixture.cpp @@ -23,7 +23,7 @@ #include "rcl/rcl.h" -#include "test_msgs/srv/primitives.h" +#include "test_msgs/srv/basic_types.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" @@ -126,8 +126,8 @@ int main(int argc, char ** argv) }); const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - test_msgs, srv, Primitives); - const char * service_name = "primitives"; + test_msgs, srv, BasicTypes); + const char * service_name = "basic_types"; rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_options_t service_options = rcl_service_get_default_options(); @@ -147,13 +147,13 @@ int main(int argc, char ** argv) }); // Initialize a response. - test_msgs__srv__Primitives_Response service_response; + test_msgs__srv__BasicTypes_Response service_response; // TODO(dirk-thomas) zero initialization necessary until // https://github.com/ros2/ros2/issues/397 is implemented - memset(&service_response, 0, sizeof(test_msgs__srv__Primitives_Response)); - test_msgs__srv__Primitives_Response__init(&service_response); + memset(&service_response, 0, sizeof(test_msgs__srv__BasicTypes_Response)); + test_msgs__srv__BasicTypes_Response__init(&service_response); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - test_msgs__srv__Primitives_Response__fini(&service_response); + test_msgs__srv__BasicTypes_Response__fini(&service_response); }); // Block until a client request comes in. @@ -164,13 +164,13 @@ int main(int argc, char ** argv) } // Take the pending request. - test_msgs__srv__Primitives_Request service_request; + test_msgs__srv__BasicTypes_Request service_request; // TODO(dirk-thomas) zero initialization necessary until // https://github.com/ros2/ros2/issues/397 is implemented - memset(&service_request, 0, sizeof(test_msgs__srv__Primitives_Request)); - test_msgs__srv__Primitives_Request__init(&service_request); + memset(&service_request, 0, sizeof(test_msgs__srv__BasicTypes_Request)); + test_msgs__srv__BasicTypes_Request__init(&service_request); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - test_msgs__srv__Primitives_Request__fini(&service_request); + test_msgs__srv__BasicTypes_Request__fini(&service_request); }); rmw_request_id_t header; // TODO(jacquelinekay) May have to check for timeout error codes diff --git a/rcl/test/rcl/test_client.cpp b/rcl/test/rcl/test_client.cpp index 3fb49a7d58..c53bfade87 100644 --- a/rcl/test/rcl/test_client.cpp +++ b/rcl/test/rcl/test_client.cpp @@ -18,8 +18,7 @@ #include "rcl/rcl.h" -#include "rosidl_generator_c/string_functions.h" -#include "test_msgs/srv/primitives.h" +#include "test_msgs/srv/basic_types.h" #include "./failing_allocator_functions.hpp" #include "osrf_testing_tools_cpp/scope_exit.hpp" @@ -76,7 +75,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( - test_msgs, srv, Primitives); + test_msgs, srv, BasicTypes); 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 @@ -89,8 +88,8 @@ TEST_F(TestClientFixture, test_client_nominal) { }); // Initialize the client request. - test_msgs__srv__Primitives_Request req; - test_msgs__srv__Primitives_Request__init(&req); + test_msgs__srv__BasicTypes_Request req; + test_msgs__srv__BasicTypes_Request__init(&req); req.uint8_value = 1; req.uint32_value = 2; @@ -110,7 +109,7 @@ TEST_F(TestClientFixture, test_client_init_fini) { rcl_client_t client; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - test_msgs, srv, Primitives); + test_msgs, srv, BasicTypes); const char * topic_name = "chatter"; rcl_client_options_t default_client_options = rcl_client_get_default_options(); diff --git a/rcl/test/rcl/test_count_matched.cpp b/rcl/test/rcl/test_count_matched.cpp index 3af13bba9f..c0eae560bf 100644 --- a/rcl/test/rcl/test_count_matched.cpp +++ b/rcl/test/rcl/test_count_matched.cpp @@ -23,8 +23,8 @@ #include "rcutils/logging_macros.h" -#include "test_msgs/msg/primitives.h" -#include "test_msgs/srv/primitives.h" +#include "test_msgs/msg/basic_types.h" +#include "test_msgs/srv/basic_types.h" #include "rcl/error_handling.h" @@ -152,7 +152,7 @@ TEST_F(CLASSNAME(TestCountFixture, RMW_IMPLEMENTATION), test_count_matched_funct rcl_publisher_t pub = rcl_get_zero_initialized_publisher(); rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options(); - auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); ret = rcl_publisher_init(&pub, this->node_ptr, ts, topic_name.c_str(), &pub_ops); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_reset_error(); @@ -202,7 +202,7 @@ TEST_F(CLASSNAME(TestCountFixture, RMW_IMPLEMENTATION), pub_ops.qos.avoid_ros_namespace_conventions = false; pub_ops.allocator = rcl_get_default_allocator(); - auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); ret = rcl_publisher_init(&pub, this->node_ptr, ts, topic_name.c_str(), &pub_ops); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_reset_error(); diff --git a/rcl/test/rcl/test_publisher.cpp b/rcl/test/rcl/test_publisher.cpp index 94dd8fd6fd..c4c95d4795 100644 --- a/rcl/test/rcl/test_publisher.cpp +++ b/rcl/test/rcl/test_publisher.cpp @@ -17,7 +17,8 @@ #include "rcl/publisher.h" #include "rcl/rcl.h" -#include "test_msgs/msg/primitives.h" +#include "test_msgs/msg/basic_types.h" +#include "test_msgs/msg/strings.h" #include "rosidl_generator_c/string_functions.h" #include "./failing_allocator_functions.hpp" @@ -78,7 +79,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); const char * topic_name = "chatter"; const char * expected_topic_name = "/chatter"; rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); @@ -89,11 +90,11 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; }); EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher), expected_topic_name), 0); - test_msgs__msg__Primitives msg; - test_msgs__msg__Primitives__init(&msg); + test_msgs__msg__BasicTypes msg; + test_msgs__msg__BasicTypes__init(&msg); msg.int64_value = 42; ret = rcl_publish(&publisher, &msg); - test_msgs__msg__Primitives__fini(&msg); + test_msgs__msg__BasicTypes__fini(&msg); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -103,7 +104,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); const char * topic_name = "chatter"; rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options); @@ -112,11 +113,11 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; }); - test_msgs__msg__Primitives msg; - test_msgs__msg__Primitives__init(&msg); + test_msgs__msg__Strings msg; + test_msgs__msg__Strings__init(&msg); ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, "testing")); ret = rcl_publish(&publisher, &msg); - test_msgs__msg__Primitives__fini(&msg); + test_msgs__msg__Strings__fini(&msg); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -130,7 +131,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts_int = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); const char * topic_name = "basename"; const char * expected_topic_name = "/basename"; rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); @@ -144,7 +145,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff rcl_publisher_t publisher_in_namespace = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts_string = ROSIDL_GET_MSG_TYPE_SUPPORT( - test_msgs, msg, Primitives); + test_msgs, msg, Strings); topic_name = "namespace/basename"; expected_topic_name = "/namespace/basename"; ret = rcl_publisher_init( @@ -156,15 +157,15 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff }); EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher_in_namespace), expected_topic_name), 0); - test_msgs__msg__Primitives msg_int; - test_msgs__msg__Primitives__init(&msg_int); + test_msgs__msg__BasicTypes msg_int; + test_msgs__msg__BasicTypes__init(&msg_int); msg_int.int64_value = 42; ret = rcl_publish(&publisher, &msg_int); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - test_msgs__msg__Primitives__fini(&msg_int); + test_msgs__msg__BasicTypes__fini(&msg_int); - test_msgs__msg__Primitives msg_string; - test_msgs__msg__Primitives__init(&msg_string); + test_msgs__msg__Strings msg_string; + test_msgs__msg__Strings__init(&msg_string); ASSERT_TRUE(rosidl_generator_c__String__assign(&msg_string.string_value, "testing")); ret = rcl_publish(&publisher_in_namespace, &msg_string); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -177,7 +178,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_ // Setup valid inputs. rcl_publisher_t publisher; const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); const char * topic_name = "chatter"; rcl_publisher_options_t default_publisher_options = rcl_publisher_get_default_options(); diff --git a/rcl/test/rcl/test_remap_integration.cpp b/rcl/test/rcl/test_remap_integration.cpp index 4ea00fc18c..b02f6d6c10 100644 --- a/rcl/test/rcl/test_remap_integration.cpp +++ b/rcl/test/rcl/test_remap_integration.cpp @@ -18,8 +18,8 @@ #include "rcl/remap.h" #include "rcl/error_handling.h" -#include "test_msgs/msg/primitives.h" -#include "test_msgs/srv/primitives.h" +#include "test_msgs/msg/basic_types.h" +#include "test_msgs/srv/basic_types.h" #include "./arg_macros.hpp" @@ -65,7 +65,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g } { // Publisher topic gets remapped const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options); @@ -75,7 +75,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g } { // Subscription topic gets remapped const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_ret_t ret = rcl_subscription_init( @@ -86,7 +86,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( - test_msgs, srv, Primitives); + test_msgs, srv, BasicTypes); 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); @@ -96,7 +96,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( - test_msgs, srv, Primitives); + test_msgs, srv, BasicTypes); 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); @@ -133,7 +133,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global } { // Publisher topic does not get remapped const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options); @@ -143,7 +143,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global } { // Subscription topic does not get remapped const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_ret_t ret = rcl_subscription_init( @@ -154,7 +154,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( - test_msgs, srv, Primitives); + test_msgs, srv, BasicTypes); 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); @@ -164,7 +164,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( - test_msgs, srv, Primitives); + test_msgs, srv, BasicTypes); 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); @@ -202,7 +202,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b } { // Publisher topic const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options); @@ -212,7 +212,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b } { // Subscription topic const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_ret_t ret = rcl_subscription_init( @@ -223,7 +223,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( - test_msgs, srv, Primitives); + test_msgs, srv, BasicTypes); 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); @@ -233,7 +233,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( - test_msgs, srv, Primitives); + test_msgs, srv, BasicTypes); 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); @@ -256,7 +256,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ { // Publisher topic const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "bar", &publisher_options); @@ -266,7 +266,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ } { // Subscription topic const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_ret_t ret = rcl_subscription_init( @@ -277,7 +277,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ } { // Client service name const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - test_msgs, srv, Primitives); + test_msgs, srv, BasicTypes); 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); @@ -287,7 +287,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ } { // Server service name const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - test_msgs, srv, Primitives); + test_msgs, srv, BasicTypes); 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 93a303fb2f..9a32c811c7 100644 --- a/rcl/test/rcl/test_service.cpp +++ b/rcl/test/rcl/test_service.cpp @@ -22,7 +22,7 @@ #include "rcl/rcl.h" -#include "test_msgs/srv/primitives.h" +#include "test_msgs/srv/basic_types.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" @@ -117,7 +117,7 @@ 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( - test_msgs, srv, Primitives); + test_msgs, srv, BasicTypes); const char * topic = "primitives"; const char * expected_topic = "/primitives"; @@ -164,8 +164,8 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) std::this_thread::sleep_for(std::chrono::milliseconds(1000)); // Initialize a request. - test_msgs__srv__Primitives_Request client_request; - test_msgs__srv__Primitives_Request__init(&client_request); + test_msgs__srv__BasicTypes_Request client_request; + test_msgs__srv__BasicTypes_Request__init(&client_request); // TODO(clalancette): the C __init methods do not initialize all structure // members, so the numbers in the fields not explicitly set is arbitrary. // The CDR deserialization in Fast-CDR requires a 0 or 1 for bool fields, @@ -177,7 +177,7 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) int64_t sequence_number; ret = rcl_send_request(&client, &client_request, &sequence_number); EXPECT_EQ(sequence_number, 1); - test_msgs__srv__Primitives_Request__fini(&client_request); + test_msgs__srv__BasicTypes_Request__fini(&client_request); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; bool success; @@ -188,15 +188,15 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) // test take_request/send_response in a single-threaded, deterministic execution. { // Initialize a response. - test_msgs__srv__Primitives_Response service_response; - test_msgs__srv__Primitives_Response__init(&service_response); + test_msgs__srv__BasicTypes_Response service_response; + test_msgs__srv__BasicTypes_Response__init(&service_response); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - test_msgs__srv__Primitives_Response__fini(&service_response); + test_msgs__srv__BasicTypes_Response__fini(&service_response); }); // Initialize a separate instance of the request and take the pending request. - test_msgs__srv__Primitives_Request service_request; - test_msgs__srv__Primitives_Request__init(&service_request); + test_msgs__srv__BasicTypes_Request service_request; + test_msgs__srv__BasicTypes_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().str; @@ -211,8 +211,8 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) wait_for_service_to_be_ready(&service, context_ptr, 10, 100, success); // Initialize the response owned by the client and take the response. - test_msgs__srv__Primitives_Response client_response; - test_msgs__srv__Primitives_Response__init(&client_response); + test_msgs__srv__BasicTypes_Response client_response; + test_msgs__srv__BasicTypes_Response__init(&client_response); rmw_request_id_t header; ret = rcl_take_response(&client, &header, &client_response); diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 1ea9710334..261b24eda3 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -21,7 +21,8 @@ #include "rcl/subscription.h" #include "rcl/rcl.h" -#include "test_msgs/msg/primitives.h" +#include "test_msgs/msg/basic_types.h" +#include "test_msgs/msg/strings.h" #include "rosidl_generator_c/string_functions.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" @@ -118,7 +119,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); const char * topic = "chatter"; const char * expected_topic = "/chatter"; rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); @@ -159,21 +160,21 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription // until then we will sleep for a short period of time std::this_thread::sleep_for(std::chrono::milliseconds(1000)); { - test_msgs__msg__Primitives msg; - test_msgs__msg__Primitives__init(&msg); + test_msgs__msg__BasicTypes msg; + test_msgs__msg__BasicTypes__init(&msg); msg.int64_value = 42; ret = rcl_publish(&publisher, &msg); - test_msgs__msg__Primitives__fini(&msg); + test_msgs__msg__BasicTypes__fini(&msg); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } bool success; wait_for_subscription_to_be_ready(&subscription, context_ptr, 10, 100, success); ASSERT_TRUE(success); { - test_msgs__msg__Primitives msg; - test_msgs__msg__Primitives__init(&msg); + test_msgs__msg__BasicTypes msg; + test_msgs__msg__BasicTypes__init(&msg); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - test_msgs__msg__Primitives__fini(&msg); + test_msgs__msg__BasicTypes__fini(&msg); }); ret = rcl_take(&subscription, &msg, nullptr); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -187,7 +188,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); const char * topic = "rcl_test_subscription_nominal_string_chatter"; rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); @@ -210,21 +211,21 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription std::this_thread::sleep_for(std::chrono::milliseconds(1000)); const char * test_string = "testing"; { - test_msgs__msg__Primitives msg; - test_msgs__msg__Primitives__init(&msg); + test_msgs__msg__Strings msg; + test_msgs__msg__Strings__init(&msg); ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, test_string)); ret = rcl_publish(&publisher, &msg); - test_msgs__msg__Primitives__fini(&msg); + test_msgs__msg__Strings__fini(&msg); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } bool success; wait_for_subscription_to_be_ready(&subscription, context_ptr, 10, 100, success); ASSERT_TRUE(success); { - test_msgs__msg__Primitives msg; - test_msgs__msg__Primitives__init(&msg); + test_msgs__msg__Strings msg; + test_msgs__msg__Strings__init(&msg); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - test_msgs__msg__Primitives__fini(&msg); + test_msgs__msg__Strings__fini(&msg); }); ret = rcl_take(&subscription, &msg, nullptr); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; diff --git a/rcl/test/test_namespace.cpp b/rcl/test/test_namespace.cpp index 18df73e0ba..9296a3b127 100644 --- a/rcl/test/test_namespace.cpp +++ b/rcl/test/test_namespace.cpp @@ -23,7 +23,7 @@ #include "rcl/graph.h" #include "rosidl_generator_c/string_functions.h" -#include "test_msgs/srv/primitives.h" +#include "test_msgs/srv/basic_types.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" @@ -75,7 +75,7 @@ class TestNamespaceFixture : public ::testing::Test */ TEST_F(TestNamespaceFixture, test_client_server) { rcl_ret_t ret; - auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, Primitives); + auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); 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";