Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

use test_msgs instead of example_interfaces #259

Merged
merged 1 commit into from
Jun 13, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion rcl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,9 @@
<test_depend>rmw</test_depend>
<test_depend>rmw_implementation_cmake</test_depend>
<test_depend>launch</test_depend>
<test_depend>example_interfaces</test_depend>
<test_depend>osrf_testing_tools_cpp</test_depend>
<test_depend>std_msgs</test_depend>
<test_depend>test_msgs</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
16 changes: 8 additions & 8 deletions rcl/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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)

Expand Down Expand Up @@ -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}
Expand Down Expand Up @@ -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}
)

Expand Down Expand Up @@ -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}
Expand All @@ -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}
Expand All @@ -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
Expand All @@ -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
Expand Down
24 changes: 12 additions & 12 deletions rcl/test/rcl/client_fixture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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())
Expand All @@ -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)) {
Expand All @@ -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")
Expand All @@ -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;
Expand Down
22 changes: 11 additions & 11 deletions rcl/test/rcl/service_fixture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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())
Expand All @@ -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.
Expand All @@ -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
Expand All @@ -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())
Expand Down
14 changes: 7 additions & 7 deletions rcl/test/rcl/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down 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(
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
Expand All @@ -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;
Expand All @@ -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();

Expand Down
4 changes: 2 additions & 2 deletions rcl/test/rcl/test_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down 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(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);
Expand Down
19 changes: 10 additions & 9 deletions rcl/test/rcl/test_remap_integration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,12 @@

#include <gtest/gtest.h>

#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"

Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand Down
Loading