diff --git a/rcl/include/rcl/client.h b/rcl/include/rcl/client.h index 9e41f7b12..eb3b46a3f 100644 --- a/rcl/include/rcl/client.h +++ b/rcl/include/rcl/client.h @@ -79,7 +79,7 @@ rcl_get_zero_initialized_client(void); * #include * * const rosidl_service_type_support_t * ts = - * ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts); + * ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts); * ``` * * For C++, a template function is used: @@ -117,7 +117,7 @@ rcl_get_zero_initialized_client(void); * rcl_ret_t ret = rcl_node_init(&node, "node_name", "/my_namespace", &node_ops); * // ... error handling * const rosidl_service_type_support_t * ts = - * ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts); + * ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts); * rcl_client_t client = rcl_get_zero_initialized_client(); * rcl_client_options_t client_ops = rcl_client_get_default_options(); * ret = rcl_client_init(&client, &node, ts, "add_two_ints", &client_ops); diff --git a/rcl/include/rcl/service.h b/rcl/include/rcl/service.h index a2fdaaaac..6e9c55f3b 100644 --- a/rcl/include/rcl/service.h +++ b/rcl/include/rcl/service.h @@ -76,7 +76,7 @@ rcl_get_zero_initialized_service(void); * #include * #include * const rosidl_service_type_support_t * ts = - * ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts); + * ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts); * ``` * * For C++, a template function is used: @@ -113,7 +113,7 @@ rcl_get_zero_initialized_service(void); * rcl_ret_t ret = rcl_node_init(&node, "node_name", "/my_namespace", &node_ops); * // ... error handling * const rosidl_service_type_support_t * ts = - * ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts); + * ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts); * rcl_service_t service = rcl_get_zero_initialized_service(); * rcl_service_options_t service_ops = rcl_service_get_default_options(); * ret = rcl_service_init(&service, &node, ts, "add_two_ints", &service_ops); diff --git a/rcl/test/rcl/client_fixture.cpp b/rcl/test/rcl/client_fixture.cpp index 05074e8a6..8af8b27cc 100644 --- a/rcl/test/rcl/client_fixture.cpp +++ b/rcl/test/rcl/client_fixture.cpp @@ -130,7 +130,7 @@ int main(int argc, char ** argv) }); const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - test_msgs, Primitives); + test_msgs, srv, Primitives); const char * service_name = "primitives"; rcl_client_t client = rcl_get_zero_initialized_client(); diff --git a/rcl/test/rcl/service_fixture.cpp b/rcl/test/rcl/service_fixture.cpp index 5071972b8..437168eff 100644 --- a/rcl/test/rcl/service_fixture.cpp +++ b/rcl/test/rcl/service_fixture.cpp @@ -103,7 +103,7 @@ int main(int argc, char ** argv) }); const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( - test_msgs, Primitives); + test_msgs, srv, Primitives); const char * service_name = "primitives"; rcl_service_t service = rcl_get_zero_initialized_service(); diff --git a/rcl/test/rcl/test_client.cpp b/rcl/test/rcl/test_client.cpp index e895a06ad..907d0f9b0 100644 --- a/rcl/test/rcl/test_client.cpp +++ b/rcl/test/rcl/test_client.cpp @@ -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( - test_msgs, Primitives); + test_msgs, srv, 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 @@ -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( - test_msgs, Primitives); + test_msgs, srv, 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 4b95ab2ca..0c347b8fc 100644 --- a/rcl/test/rcl/test_graph.cpp +++ b/rcl/test/rcl/test_graph.cpp @@ -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(test_msgs, Primitives); + auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, 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 859c2199c..155da3cad 100644 --- a/rcl/test/rcl/test_remap_integration.cpp +++ b/rcl/test/rcl/test_remap_integration.cpp @@ -84,7 +84,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, Primitives); + test_msgs, srv, 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); @@ -94,7 +94,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, Primitives); + test_msgs, srv, 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); @@ -152,7 +152,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, Primitives); + test_msgs, srv, 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); @@ -162,7 +162,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, Primitives); + test_msgs, srv, 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); @@ -221,7 +221,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, Primitives); + test_msgs, srv, 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); @@ -231,7 +231,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, Primitives); + test_msgs, srv, 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); @@ -275,7 +275,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, Primitives); + test_msgs, srv, 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); @@ -285,7 +285,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, Primitives); + test_msgs, srv, 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 fb0e519c0..b54fa6242 100644 --- a/rcl/test/rcl/test_service.cpp +++ b/rcl/test/rcl/test_service.cpp @@ -102,7 +102,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, Primitives); + test_msgs, srv, Primitives); const char * topic = "primitives"; const char * expected_topic = "/primitives"; diff --git a/rcl/test/test_namespace.cpp b/rcl/test/test_namespace.cpp index ec490b77b..f25a80df5 100644 --- a/rcl/test/test_namespace.cpp +++ b/rcl/test/test_namespace.cpp @@ -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(test_msgs, Primitives); + auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, 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";