Skip to content

Commit

Permalink
Add subfolder argument to the ROSIDL_GET_SRV_TYPE_SUPPORT macro (#322)
Browse files Browse the repository at this point in the history
  • Loading branch information
jacobperron authored Nov 8, 2018
1 parent e6985c0 commit 5d12f54
Show file tree
Hide file tree
Showing 9 changed files with 19 additions and 19 deletions.
4 changes: 2 additions & 2 deletions rcl/include/rcl/client.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ rcl_get_zero_initialized_client(void);
* #include <example_interfaces/srv/add_two_ints.h>
*
* 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:
Expand Down Expand Up @@ -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);
Expand Down
4 changes: 2 additions & 2 deletions rcl/include/rcl/service.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ rcl_get_zero_initialized_service(void);
* #include <rosidl_generator_c/service_type_support_struct.h>
* #include <example_interfaces/srv/add_two_ints.h>
* 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:
Expand Down Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion rcl/test/rcl/client_fixture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
2 changes: 1 addition & 1 deletion rcl/test/rcl/service_fixture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
4 changes: 2 additions & 2 deletions rcl/test/rcl/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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();

Expand Down
2 changes: 1 addition & 1 deletion rcl/test/rcl/test_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
16 changes: 8 additions & 8 deletions rcl/test/rcl/test_remap_integration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion rcl/test/rcl/test_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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";

Expand Down
2 changes: 1 addition & 1 deletion rcl/test/test_namespace.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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";
Expand Down

0 comments on commit 5d12f54

Please sign in to comment.