Add subfolder argument to the ROSIDL_GET_SRV_TYPE_SUPPORT macro (#322)

This commit is contained in:
Jacob Perron 2018-11-08 09:49:21 -08:00 committed by GitHub
parent e6985c0226
commit 5d12f54d13
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
9 changed files with 19 additions and 19 deletions

View file

@ -79,7 +79,7 @@ rcl_get_zero_initialized_client(void);
* #include <example_interfaces/srv/add_two_ints.h> * #include <example_interfaces/srv/add_two_ints.h>
* *
* const rosidl_service_type_support_t * ts = * 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: * 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); * rcl_ret_t ret = rcl_node_init(&node, "node_name", "/my_namespace", &node_ops);
* // ... error handling * // ... error handling
* const rosidl_service_type_support_t * ts = * 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_t client = rcl_get_zero_initialized_client();
* rcl_client_options_t client_ops = rcl_client_get_default_options(); * rcl_client_options_t client_ops = rcl_client_get_default_options();
* ret = rcl_client_init(&client, &node, ts, "add_two_ints", &client_ops); * ret = rcl_client_init(&client, &node, ts, "add_two_ints", &client_ops);

View file

@ -76,7 +76,7 @@ rcl_get_zero_initialized_service(void);
* #include <rosidl_generator_c/service_type_support_struct.h> * #include <rosidl_generator_c/service_type_support_struct.h>
* #include <example_interfaces/srv/add_two_ints.h> * #include <example_interfaces/srv/add_two_ints.h>
* const rosidl_service_type_support_t * ts = * 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: * 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); * rcl_ret_t ret = rcl_node_init(&node, "node_name", "/my_namespace", &node_ops);
* // ... error handling * // ... error handling
* const rosidl_service_type_support_t * ts = * 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_t service = rcl_get_zero_initialized_service();
* rcl_service_options_t service_ops = rcl_service_get_default_options(); * rcl_service_options_t service_ops = rcl_service_get_default_options();
* ret = rcl_service_init(&service, &node, ts, "add_two_ints", &service_ops); * ret = rcl_service_init(&service, &node, ts, "add_two_ints", &service_ops);

View file

@ -130,7 +130,7 @@ int main(int argc, char ** argv)
}); });
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(
test_msgs, Primitives); test_msgs, srv, Primitives);
const char * service_name = "primitives"; const char * service_name = "primitives";
rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_t client = rcl_get_zero_initialized_client();

View file

@ -103,7 +103,7 @@ int main(int argc, char ** argv)
}); });
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(
test_msgs, Primitives); test_msgs, srv, Primitives);
const char * service_name = "primitives"; const char * service_name = "primitives";
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();

View file

@ -64,7 +64,7 @@ TEST_F(TestClientFixture, test_client_nominal) {
rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_options_t client_options = rcl_client_get_default_options();
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( 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); 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 // 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; rcl_client_t client;
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(
test_msgs, Primitives); test_msgs, srv, Primitives);
const char * topic_name = "chatter"; const char * topic_name = "chatter";
rcl_client_options_t default_client_options = rcl_client_get_default_options(); rcl_client_options_t default_client_options = rcl_client_get_default_options();

View file

@ -469,7 +469,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_
rcl_ret_t ret; rcl_ret_t ret;
// First create a client which will be used to call the function. // First create a client which will be used to call the function.
rcl_client_t client = rcl_get_zero_initialized_client(); 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"; const char * service_name = "/service_test_rcl_service_server_is_available";
rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_options_t client_options = rcl_client_get_default_options();
ret = rcl_client_init(&client, this->node_ptr, ts, service_name, &client_options); ret = rcl_client_init(&client, this->node_ptr, ts, service_name, &client_options);

View file

@ -84,7 +84,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g
} }
{ // Client service name gets remapped { // Client service name gets remapped
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( 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_options_t client_options = rcl_client_get_default_options();
rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_t client = rcl_get_zero_initialized_client();
rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options); 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 { // Server service name gets remapped
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( 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_options_t service_options = rcl_service_get_default_options();
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();
rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options); 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 { // Client service name does not get remapped
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( 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_options_t client_options = rcl_client_get_default_options();
rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_t client = rcl_get_zero_initialized_client();
rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options); 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 { // Server service name does not get remapped
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( 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_options_t service_options = rcl_service_get_default_options();
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();
rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options); 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 { // Client service name
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( 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_options_t client_options = rcl_client_get_default_options();
rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_t client = rcl_get_zero_initialized_client();
rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options); 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 { // Server service name
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( 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_options_t service_options = rcl_service_get_default_options();
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();
rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options); 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 { // Client service name
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( 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_options_t client_options = rcl_client_get_default_options();
rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_t client = rcl_get_zero_initialized_client();
rcl_ret_t ret = rcl_client_init(&client, &node, ts, "bar", &client_options); 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 { // Server service name
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( 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_options_t service_options = rcl_service_get_default_options();
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();
rcl_ret_t ret = rcl_service_init(&service, &node, ts, "bar", &service_options); rcl_ret_t ret = rcl_service_init(&service, &node, ts, "bar", &service_options);

View file

@ -102,7 +102,7 @@ wait_for_service_to_be_ready(
TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) { TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) {
rcl_ret_t ret; rcl_ret_t ret;
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( 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 * topic = "primitives";
const char * expected_topic = "/primitives"; const char * expected_topic = "/primitives";

View file

@ -61,7 +61,7 @@ public:
*/ */
TEST_F(TestNamespaceFixture, test_client_server) { TEST_F(TestNamespaceFixture, test_client_server) {
rcl_ret_t ret; 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 * service_name = "/my/namespace/test_namespace_client_server";
const char * unmatched_client_name = "/your/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"; const char * matched_client_name = "/my/namespace/test_namespace_client_server";