Add tests for rcl package (#668)
* Add tests for node_options usage * Add tests for copying options arguments * Add bad argument tests for wait sets * Add tests for wait_set_get_allocator function * Add test for rcl_take_response function * Change take_request to match take_response without info * Change specific test for sequence_number * Add tests for client take failed * Remove tests already done in nominal setup * Add bad arguments tests * Add test for init returning BAD_ALLOC * Add test for client get_options * Add test for already init client * Add bad argument tests * Add basic test get_default_domain_id * Add test for rmw to rcl return code function * Add test for get_localhost_only * Add tests for localhost expected usage * Address peer review comments * Add test for env variable leading to ULONG_MAX * Change return values to enum in test * Fix rcl_get_localhost_only return value * Address peer review comments * Add unexpected value to get_localhost * Add reset_rcl_error after expected fails Signed-off-by: Jorge Perez <jjperez@ekumenlabs.com>
This commit is contained in:
parent
c70774659d
commit
d663b4b9b7
8 changed files with 502 additions and 1 deletions
|
@ -326,6 +326,18 @@ rcl_add_custom_gtest(test_validate_enclave_name
|
||||||
LIBRARIES ${PROJECT_NAME}
|
LIBRARIES ${PROJECT_NAME}
|
||||||
)
|
)
|
||||||
|
|
||||||
|
rcl_add_custom_gtest(test_domain_id
|
||||||
|
SRCS rcl/test_domain_id.cpp
|
||||||
|
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||||
|
LIBRARIES ${PROJECT_NAME}
|
||||||
|
)
|
||||||
|
|
||||||
|
rcl_add_custom_gtest(test_localhost
|
||||||
|
SRCS rcl/test_localhost.cpp
|
||||||
|
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||||
|
LIBRARIES ${PROJECT_NAME}
|
||||||
|
)
|
||||||
|
|
||||||
rcl_add_custom_gtest(test_validate_topic_name
|
rcl_add_custom_gtest(test_validate_topic_name
|
||||||
SRCS rcl/test_validate_topic_name.cpp
|
SRCS rcl/test_validate_topic_name.cpp
|
||||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||||
|
@ -352,6 +364,13 @@ rcl_add_custom_gtest(test_security
|
||||||
AMENT_DEPENDENCIES "osrf_testing_tools_cpp"
|
AMENT_DEPENDENCIES "osrf_testing_tools_cpp"
|
||||||
)
|
)
|
||||||
|
|
||||||
|
rcl_add_custom_gtest(test_common
|
||||||
|
SRCS rcl/test_common.cpp ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/common.c
|
||||||
|
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||||
|
INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/
|
||||||
|
LIBRARIES ${PROJECT_NAME}
|
||||||
|
)
|
||||||
|
|
||||||
# Install test resources
|
# Install test resources
|
||||||
install(DIRECTORY ${test_resources_dir_name}
|
install(DIRECTORY ${test_resources_dir_name}
|
||||||
DESTINATION ${CMAKE_CURRENT_BINARY_DIR})
|
DESTINATION ${CMAKE_CURRENT_BINARY_DIR})
|
||||||
|
|
|
@ -67,7 +67,7 @@ public:
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
/* Basic nominal test of a client.
|
/* Basic nominal test of a client. Complete functionality tested at test_service.cpp
|
||||||
*/
|
*/
|
||||||
TEST_F(TestClientFixture, test_client_nominal) {
|
TEST_F(TestClientFixture, test_client_nominal) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
|
@ -82,6 +82,14 @@ TEST_F(TestClientFixture, test_client_nominal) {
|
||||||
test_msgs, srv, BasicTypes);
|
test_msgs, srv, BasicTypes);
|
||||||
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);
|
||||||
|
|
||||||
|
// Test access to client options
|
||||||
|
const rcl_client_options_t * client_internal_options = rcl_client_get_options(&client);
|
||||||
|
EXPECT_TRUE(rcutils_allocator_is_valid(&(client_internal_options->allocator)));
|
||||||
|
EXPECT_EQ(rmw_qos_profile_services_default.reliability, client_internal_options->qos.reliability);
|
||||||
|
EXPECT_EQ(rmw_qos_profile_services_default.history, client_internal_options->qos.history);
|
||||||
|
EXPECT_EQ(rmw_qos_profile_services_default.depth, client_internal_options->qos.depth);
|
||||||
|
EXPECT_EQ(rmw_qos_profile_services_default.durability, client_internal_options->qos.durability);
|
||||||
|
|
||||||
// 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
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
EXPECT_EQ(strcmp(rcl_client_get_service_name(&client), expected_topic_name), 0);
|
EXPECT_EQ(strcmp(rcl_client_get_service_name(&client), expected_topic_name), 0);
|
||||||
|
@ -144,6 +152,8 @@ TEST_F(TestClientFixture, test_client_init_fini) {
|
||||||
ret = rcl_client_init(&client, this->node_ptr, ts, topic_name, &default_client_options);
|
ret = rcl_client_init(&client, this->node_ptr, ts, topic_name, &default_client_options);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
EXPECT_TRUE(rcl_client_is_valid(&client));
|
EXPECT_TRUE(rcl_client_is_valid(&client));
|
||||||
|
ret = rcl_client_init(&client, this->node_ptr, ts, topic_name, &default_client_options);
|
||||||
|
EXPECT_EQ(RCL_RET_ALREADY_INIT, ret) << rcl_get_error_string().str;
|
||||||
ret = rcl_client_fini(&client, this->node_ptr);
|
ret = rcl_client_fini(&client, this->node_ptr);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
|
@ -206,3 +216,64 @@ TEST_F(TestClientFixture, test_client_init_fini) {
|
||||||
EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string().str;
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* Passing bad/invalid arguments to the functions
|
||||||
|
*/
|
||||||
|
TEST_F(TestClientFixture, test_client_bad_arguments) {
|
||||||
|
rcl_client_t client = rcl_get_zero_initialized_client();
|
||||||
|
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(
|
||||||
|
test_msgs, srv, BasicTypes);
|
||||||
|
rcl_client_options_t default_client_options = rcl_client_get_default_options();
|
||||||
|
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_SERVICE_NAME_INVALID, rcl_client_init(
|
||||||
|
&client, this->node_ptr, ts,
|
||||||
|
"invalid name", &default_client_options)) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
EXPECT_EQ(RCL_RET_NODE_INVALID, rcl_client_fini(&client, nullptr));
|
||||||
|
rcl_node_t not_valid_node = rcl_get_zero_initialized_node();
|
||||||
|
EXPECT_EQ(RCL_RET_NODE_INVALID, rcl_client_fini(&client, ¬_valid_node));
|
||||||
|
|
||||||
|
rmw_service_info_t header;
|
||||||
|
int64_t sequence_number = 24;
|
||||||
|
test_msgs__srv__BasicTypes_Response client_response;
|
||||||
|
test_msgs__srv__BasicTypes_Request client_request;
|
||||||
|
test_msgs__srv__BasicTypes_Request__init(&client_request);
|
||||||
|
test_msgs__srv__BasicTypes_Response__init(&client_response);
|
||||||
|
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||||
|
{
|
||||||
|
test_msgs__srv__BasicTypes_Response__fini(&client_response);
|
||||||
|
test_msgs__srv__BasicTypes_Request__fini(&client_request);
|
||||||
|
});
|
||||||
|
|
||||||
|
EXPECT_EQ(nullptr, rcl_client_get_rmw_handle(nullptr));
|
||||||
|
EXPECT_EQ(nullptr, rcl_client_get_service_name(nullptr));
|
||||||
|
EXPECT_EQ(nullptr, rcl_client_get_service_name(nullptr));
|
||||||
|
EXPECT_EQ(nullptr, rcl_client_get_options(nullptr));
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_CLIENT_INVALID, rcl_take_response_with_info(
|
||||||
|
nullptr, &header, &client_response)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_CLIENT_INVALID, rcl_take_response(
|
||||||
|
nullptr, &(header.request_id), &client_response)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_CLIENT_INVALID, rcl_send_request(
|
||||||
|
nullptr, &client_request, &sequence_number)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(24, sequence_number);
|
||||||
|
|
||||||
|
// Not init client
|
||||||
|
EXPECT_EQ(nullptr, rcl_client_get_rmw_handle(&client));
|
||||||
|
EXPECT_EQ(nullptr, rcl_client_get_service_name(&client));
|
||||||
|
EXPECT_EQ(nullptr, rcl_client_get_service_name(&client));
|
||||||
|
EXPECT_EQ(nullptr, rcl_client_get_options(&client));
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_CLIENT_INVALID, rcl_take_response_with_info(
|
||||||
|
&client, &header, &client_response)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_CLIENT_INVALID, rcl_take_response(
|
||||||
|
&client, &(header.request_id), &client_response)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_CLIENT_INVALID, rcl_send_request(
|
||||||
|
&client, &client_request, &sequence_number)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(24, sequence_number);
|
||||||
|
}
|
||||||
|
|
34
rcl/test/rcl/test_common.cpp
Normal file
34
rcl/test/rcl/test_common.cpp
Normal file
|
@ -0,0 +1,34 @@
|
||||||
|
// Copyright 2020 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include <gtest/gtest.h>
|
||||||
|
|
||||||
|
#include "rcl/rcl.h"
|
||||||
|
#include "./common.h"
|
||||||
|
|
||||||
|
// This function is not part of the public API
|
||||||
|
TEST(TestCommonFunctionality, test_rmw_ret_to_rcl_ret) {
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_convert_rmw_ret_to_rcl_ret(RMW_RET_OK));
|
||||||
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_convert_rmw_ret_to_rcl_ret(RMW_RET_INVALID_ARGUMENT));
|
||||||
|
EXPECT_EQ(RCL_RET_BAD_ALLOC, rcl_convert_rmw_ret_to_rcl_ret(RMW_RET_BAD_ALLOC));
|
||||||
|
EXPECT_EQ(RCL_RET_UNSUPPORTED, rcl_convert_rmw_ret_to_rcl_ret(RMW_RET_UNSUPPORTED));
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_NODE_NAME_NON_EXISTENT,
|
||||||
|
rcl_convert_rmw_ret_to_rcl_ret(RMW_RET_NODE_NAME_NON_EXISTENT));
|
||||||
|
|
||||||
|
// Default behavior
|
||||||
|
EXPECT_EQ(RCL_RET_ERROR, rcl_convert_rmw_ret_to_rcl_ret(RMW_RET_ERROR));
|
||||||
|
EXPECT_EQ(RCL_RET_ERROR, rcl_convert_rmw_ret_to_rcl_ret(RMW_RET_TIMEOUT));
|
||||||
|
EXPECT_EQ(RCL_RET_ERROR, rcl_convert_rmw_ret_to_rcl_ret(RMW_RET_INCORRECT_RMW_IMPLEMENTATION));
|
||||||
|
}
|
36
rcl/test/rcl/test_domain_id.cpp
Normal file
36
rcl/test/rcl/test_domain_id.cpp
Normal file
|
@ -0,0 +1,36 @@
|
||||||
|
// Copyright 2020 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include <gtest/gtest.h>
|
||||||
|
|
||||||
|
#include "rcl/rcl.h"
|
||||||
|
|
||||||
|
#include "rcl/domain_id.h"
|
||||||
|
#include "rcl/error_handling.h"
|
||||||
|
#include "rcutils/env.h"
|
||||||
|
|
||||||
|
TEST(TestGetDomainId, test_nominal) {
|
||||||
|
ASSERT_TRUE(rcutils_set_env("ROS_DOMAIN_ID", "42"));
|
||||||
|
size_t domain_id = 0u;
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_get_default_domain_id(&domain_id));
|
||||||
|
EXPECT_EQ(42u, domain_id);
|
||||||
|
|
||||||
|
ASSERT_TRUE(rcutils_set_env("ROS_DOMAIN_ID", "998446744073709551615"));
|
||||||
|
domain_id = 0u;
|
||||||
|
EXPECT_EQ(RCL_RET_ERROR, rcl_get_default_domain_id(&domain_id));
|
||||||
|
rcl_reset_error();
|
||||||
|
EXPECT_EQ(0u, domain_id);
|
||||||
|
|
||||||
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_get_default_domain_id(nullptr));
|
||||||
|
}
|
41
rcl/test/rcl/test_localhost.cpp
Normal file
41
rcl/test/rcl/test_localhost.cpp
Normal file
|
@ -0,0 +1,41 @@
|
||||||
|
// Copyright 2020 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include <gtest/gtest.h>
|
||||||
|
|
||||||
|
#include "rcl/rcl.h"
|
||||||
|
#include "rcl/localhost.h"
|
||||||
|
#include "rmw/localhost.h"
|
||||||
|
#include "rcutils/env.h"
|
||||||
|
|
||||||
|
TEST(TestLocalhost, test_get_localhost_only) {
|
||||||
|
ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "0"));
|
||||||
|
rmw_localhost_only_t localhost_var;
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_get_localhost_only(&localhost_var));
|
||||||
|
EXPECT_EQ(RMW_LOCALHOST_ONLY_DISABLED, localhost_var);
|
||||||
|
|
||||||
|
ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "1"));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_get_localhost_only(&localhost_var));
|
||||||
|
EXPECT_EQ(RMW_LOCALHOST_ONLY_ENABLED, localhost_var);
|
||||||
|
|
||||||
|
ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "2"));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_get_localhost_only(&localhost_var));
|
||||||
|
EXPECT_EQ(RMW_LOCALHOST_ONLY_DISABLED, localhost_var);
|
||||||
|
|
||||||
|
ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "Unexpected"));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_get_localhost_only(&localhost_var));
|
||||||
|
EXPECT_EQ(RMW_LOCALHOST_ONLY_DISABLED, localhost_var);
|
||||||
|
|
||||||
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_get_localhost_only(nullptr));
|
||||||
|
}
|
|
@ -745,3 +745,50 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names) {
|
||||||
EXPECT_EQ(RCL_RET_OK, ret);
|
EXPECT_EQ(RCL_RET_OK, ret);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* Tests the node_options functionality
|
||||||
|
*/
|
||||||
|
TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_options) {
|
||||||
|
rcl_node_options_t default_options = rcl_node_get_default_options();
|
||||||
|
rcl_node_options_t not_ini_options = rcl_node_get_default_options();
|
||||||
|
|
||||||
|
EXPECT_TRUE(default_options.use_global_arguments);
|
||||||
|
EXPECT_TRUE(default_options.enable_rosout);
|
||||||
|
EXPECT_EQ(RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID, default_options.domain_id);
|
||||||
|
EXPECT_TRUE(rcutils_allocator_is_valid(&(default_options.allocator)));
|
||||||
|
|
||||||
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_node_options_copy(nullptr, &default_options));
|
||||||
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_node_options_copy(&default_options, nullptr));
|
||||||
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_node_options_copy(&default_options, &default_options));
|
||||||
|
|
||||||
|
const char * argv[] = {
|
||||||
|
"process_name", "--ros-args", "/foo/bar:=", "-r", "bar:=/fiz/buz", "}bar:=fiz", "--", "arg"};
|
||||||
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_OK,
|
||||||
|
rcl_parse_arguments(argc, argv, default_options.allocator, &(default_options.arguments)));
|
||||||
|
default_options.domain_id = 42u;
|
||||||
|
default_options.use_global_arguments = false;
|
||||||
|
default_options.enable_rosout = false;
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_node_options_copy(&default_options, ¬_ini_options));
|
||||||
|
EXPECT_EQ(42u, not_ini_options.domain_id);
|
||||||
|
EXPECT_FALSE(not_ini_options.use_global_arguments);
|
||||||
|
EXPECT_FALSE(not_ini_options.enable_rosout);
|
||||||
|
EXPECT_EQ(
|
||||||
|
rcl_arguments_get_count_unparsed(&(default_options.arguments)),
|
||||||
|
rcl_arguments_get_count_unparsed(&(not_ini_options.arguments)));
|
||||||
|
EXPECT_EQ(
|
||||||
|
rcl_arguments_get_count_unparsed_ros(&(default_options.arguments)),
|
||||||
|
rcl_arguments_get_count_unparsed_ros(&(not_ini_options.arguments)));
|
||||||
|
|
||||||
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_node_options_fini(nullptr));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_node_options_fini(&default_options));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_node_options_fini(¬_ini_options));
|
||||||
|
|
||||||
|
// (TODO: blast545) will be fixed with: https://github.com/ros2/rcl/pull/671
|
||||||
|
// This causes the test suite to fail:
|
||||||
|
// rcl_node_options_t default_options = rcl_node_get_default_options();
|
||||||
|
// rcl_node_options_t not_ini_options;
|
||||||
|
// EXPECT_EQ(RCL_RET_OK, rcl_node_options_copy(&default_options, ¬_ini_options));
|
||||||
|
// EXPECT_EQ(RCL_RET_OK, rcl_node_options_fini(¬_ini_options)); <-- code fails, returns -11
|
||||||
|
}
|
||||||
|
|
|
@ -22,6 +22,7 @@
|
||||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
#include "wait_for_entity_helpers.hpp"
|
#include "wait_for_entity_helpers.hpp"
|
||||||
|
#include "./allocator_testing_utils.h"
|
||||||
|
|
||||||
#ifdef RMW_IMPLEMENTATION
|
#ifdef RMW_IMPLEMENTATION
|
||||||
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
|
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
|
||||||
|
@ -85,6 +86,10 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal)
|
||||||
rcl_service_options_t service_options = rcl_service_get_default_options();
|
rcl_service_options_t service_options = rcl_service_get_default_options();
|
||||||
ret = rcl_service_init(&service, this->node_ptr, ts, topic, &service_options);
|
ret = rcl_service_init(&service, this->node_ptr, ts, topic, &service_options);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
ret = rcl_service_init(&service, this->node_ptr, ts, topic, &service_options);
|
||||||
|
EXPECT_EQ(RCL_RET_ALREADY_INIT, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
ret = rcl_service_fini(&service, this->node_ptr);
|
ret = rcl_service_fini(&service, this->node_ptr);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
@ -210,5 +215,190 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal)
|
||||||
EXPECT_EQ(0u, header.received_timestamp);
|
EXPECT_EQ(0u, header.received_timestamp);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
ret = rcl_take_response_with_info(&client, &header, &client_response);
|
||||||
|
EXPECT_EQ(RCL_RET_CLIENT_TAKE_FAILED, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
test_msgs__srv__BasicTypes_Response__fini(&client_response);
|
test_msgs__srv__BasicTypes_Response__fini(&client_response);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* Basic nominal test of a service with rcl_take_response
|
||||||
|
*/
|
||||||
|
TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_without_info) {
|
||||||
|
rcl_ret_t ret;
|
||||||
|
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(
|
||||||
|
test_msgs, srv, BasicTypes);
|
||||||
|
const char * topic = "primitives";
|
||||||
|
const char * expected_topic = "/primitives";
|
||||||
|
|
||||||
|
rcl_service_t service = rcl_get_zero_initialized_service();
|
||||||
|
rcl_service_options_t service_options = rcl_service_get_default_options();
|
||||||
|
ret = rcl_service_init(&service, this->node_ptr, ts, topic, &service_options);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
EXPECT_TRUE(rcl_service_is_valid(&service));
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
// Check that the service name matches what we assigned.
|
||||||
|
EXPECT_STREQ(rcl_service_get_service_name(&service), expected_topic);
|
||||||
|
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||||
|
{
|
||||||
|
rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
});
|
||||||
|
|
||||||
|
rcl_client_t client = rcl_get_zero_initialized_client();
|
||||||
|
rcl_client_options_t client_options = rcl_client_get_default_options();
|
||||||
|
ret = rcl_client_init(&client, this->node_ptr, ts, topic, &client_options);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||||
|
{
|
||||||
|
rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
});
|
||||||
|
|
||||||
|
ASSERT_TRUE(wait_for_server_to_be_available(this->node_ptr, &client, 10, 1000));
|
||||||
|
|
||||||
|
// Initialize a 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,
|
||||||
|
// so we explicitly initialize that even though we don't use it. This can be
|
||||||
|
// removed once the C __init methods initialize all members by default.
|
||||||
|
client_request.bool_value = false;
|
||||||
|
client_request.uint8_value = 1;
|
||||||
|
client_request.uint32_value = 2;
|
||||||
|
int64_t sequence_number = 0;
|
||||||
|
ret = rcl_send_request(&client, &client_request, &sequence_number);
|
||||||
|
EXPECT_NE(sequence_number, 0);
|
||||||
|
test_msgs__srv__BasicTypes_Request__fini(&client_request);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
ASSERT_TRUE(wait_for_service_to_be_ready(&service, context_ptr, 10, 100));
|
||||||
|
|
||||||
|
// This scope simulates the service responding in a different context so that we can
|
||||||
|
// test take_request/send_response in a single-threaded, deterministic execution.
|
||||||
|
{
|
||||||
|
// Initialize a 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__BasicTypes_Response__fini(&service_response);
|
||||||
|
});
|
||||||
|
|
||||||
|
// Initialize a separate instance of the request and take the pending request.
|
||||||
|
test_msgs__srv__BasicTypes_Request service_request;
|
||||||
|
test_msgs__srv__BasicTypes_Request__init(&service_request);
|
||||||
|
rmw_service_info_t header;
|
||||||
|
ret = rcl_take_request(&service, &(header.request_id), &service_request);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
EXPECT_EQ(1, service_request.uint8_value);
|
||||||
|
EXPECT_EQ(2UL, service_request.uint32_value);
|
||||||
|
// Simulate a response callback by summing the request and send the response..
|
||||||
|
service_response.uint64_value = service_request.uint8_value + service_request.uint32_value;
|
||||||
|
ret = rcl_send_response(&service, &header.request_id, &service_response);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
test_msgs__srv__BasicTypes_Request__fini(&service_request);
|
||||||
|
}
|
||||||
|
ASSERT_FALSE(wait_for_service_to_be_ready(&service, context_ptr, 10, 100));
|
||||||
|
|
||||||
|
// Initialize the response owned by the client and take the response.
|
||||||
|
test_msgs__srv__BasicTypes_Response client_response;
|
||||||
|
test_msgs__srv__BasicTypes_Response__init(&client_response);
|
||||||
|
|
||||||
|
rmw_service_info_t header;
|
||||||
|
ret = rcl_take_response(&client, &(header.request_id), &client_response);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(client_response.uint64_value, 3ULL);
|
||||||
|
EXPECT_NE(header.request_id.sequence_number, 0);
|
||||||
|
|
||||||
|
ret = rcl_take_response(&client, &(header.request_id), &client_response);
|
||||||
|
EXPECT_EQ(RCL_RET_CLIENT_TAKE_FAILED, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
test_msgs__srv__BasicTypes_Response__fini(&client_response);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Passing bad/invalid arguments to service functions
|
||||||
|
*/
|
||||||
|
TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_bad_arguments) {
|
||||||
|
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(
|
||||||
|
test_msgs, srv, BasicTypes);
|
||||||
|
const char * topic = "primitives";
|
||||||
|
|
||||||
|
rcl_service_t service = rcl_get_zero_initialized_service();
|
||||||
|
rcl_service_options_t service_options = rcl_service_get_default_options();
|
||||||
|
|
||||||
|
rcl_service_options_t service_options_bad_alloc = rcl_service_get_default_options();
|
||||||
|
service_options_bad_alloc.allocator.allocate = nullptr;
|
||||||
|
rcl_node_t invalid_node = rcl_get_zero_initialized_node();
|
||||||
|
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_NODE_INVALID, rcl_service_init(
|
||||||
|
&service, nullptr, ts, topic, &service_options)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_NODE_INVALID, rcl_service_init(
|
||||||
|
&service, &invalid_node, ts, topic, &service_options)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_INVALID_ARGUMENT, rcl_service_init(
|
||||||
|
nullptr, this->node_ptr, ts, topic, &service_options)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_INVALID_ARGUMENT, rcl_service_init(
|
||||||
|
&service, this->node_ptr, nullptr, topic, &service_options)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_INVALID_ARGUMENT, rcl_service_init(
|
||||||
|
&service, this->node_ptr, ts, nullptr, &service_options)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_INVALID_ARGUMENT, rcl_service_init(
|
||||||
|
&service, this->node_ptr, ts, topic, nullptr)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_INVALID_ARGUMENT, rcl_service_init(
|
||||||
|
&service, this->node_ptr, ts, topic,
|
||||||
|
&service_options_bad_alloc)) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_NODE_INVALID, rcl_service_fini(&service, nullptr)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_NODE_INVALID, rcl_service_fini(&service, &invalid_node)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_SERVICE_INVALID, rcl_service_fini(
|
||||||
|
nullptr, this->node_ptr)) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
test_msgs__srv__BasicTypes_Request service_request;
|
||||||
|
test_msgs__srv__BasicTypes_Response service_response;
|
||||||
|
test_msgs__srv__BasicTypes_Request__init(&service_request);
|
||||||
|
test_msgs__srv__BasicTypes_Response__init(&service_response);
|
||||||
|
rmw_service_info_t header;
|
||||||
|
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||||
|
{
|
||||||
|
test_msgs__srv__BasicTypes_Request__fini(&service_request);
|
||||||
|
test_msgs__srv__BasicTypes_Response__fini(&service_response);
|
||||||
|
});
|
||||||
|
|
||||||
|
EXPECT_EQ(nullptr, rcl_service_get_service_name(nullptr));
|
||||||
|
EXPECT_EQ(nullptr, rcl_service_get_options(nullptr));
|
||||||
|
EXPECT_EQ(nullptr, rcl_service_get_rmw_handle(nullptr));
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_SERVICE_INVALID, rcl_take_request_with_info(nullptr, &header, &service_request));
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_SERVICE_INVALID, rcl_send_response(nullptr, &header.request_id, &service_response));
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_SERVICE_INVALID, rcl_take_request(nullptr, &(header.request_id), &service_request));
|
||||||
|
|
||||||
|
EXPECT_EQ(nullptr, rcl_service_get_service_name(&service));
|
||||||
|
EXPECT_EQ(nullptr, rcl_service_get_options(&service));
|
||||||
|
EXPECT_EQ(nullptr, rcl_service_get_rmw_handle(&service));
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_SERVICE_INVALID, rcl_take_request_with_info(&service, &header, &service_request));
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_SERVICE_INVALID, rcl_send_response(&service, &(header.request_id), &service_response));
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_SERVICE_INVALID, rcl_take_request(&service, &(header.request_id), &service_request));
|
||||||
|
|
||||||
|
service_options_bad_alloc.allocator = get_failing_allocator();
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_BAD_ALLOC, rcl_service_init(
|
||||||
|
&service, this->node_ptr, ts,
|
||||||
|
topic, &service_options_bad_alloc)) << rcl_get_error_string().str;
|
||||||
|
}
|
||||||
|
|
|
@ -553,3 +553,66 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), add_with_index) {
|
||||||
EXPECT_EQ(&guard_conditions[i], wait_set.guard_conditions[i]);
|
EXPECT_EQ(&guard_conditions[i], wait_set.guard_conditions[i]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Extra invalid arguments not tested
|
||||||
|
TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_valid_arguments) {
|
||||||
|
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
||||||
|
rcl_ret_t ret =
|
||||||
|
rcl_wait_set_init(&wait_set, 0, 0, 0, 0, 0, 0, context_ptr, rcl_get_default_allocator());
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_WAIT_SET_EMPTY, rcl_wait(&wait_set, RCL_MS_TO_NS(1000))) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_wait_set_fini(&wait_set)) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_INVALID_ARGUMENT, rcl_wait(nullptr, RCL_MS_TO_NS(1000))) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_WAIT_SET_INVALID,
|
||||||
|
rcl_wait(&wait_set, RCL_MS_TO_NS(1000))) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
rcl_context_t not_init_context = rcl_get_zero_initialized_context();
|
||||||
|
ret =
|
||||||
|
rcl_wait_set_init(&wait_set, 1, 1, 1, 1, 1, 0, ¬_init_context, rcl_get_default_allocator());
|
||||||
|
EXPECT_EQ(RCL_RET_NOT_INIT, ret) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
ret =
|
||||||
|
rcl_wait_set_init(&wait_set, 1, 1, 1, 1, 1, 0, context_ptr, rcl_get_default_allocator());
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
ret =
|
||||||
|
rcl_wait_set_init(&wait_set, 1, 1, 1, 1, 1, 0, context_ptr, rcl_get_default_allocator());
|
||||||
|
EXPECT_EQ(RCL_RET_ALREADY_INIT, ret) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
ret = rcl_wait_set_fini(&wait_set);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Test get allocator function
|
||||||
|
TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_get_allocator) {
|
||||||
|
rcl_allocator_t allocator_returned;
|
||||||
|
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
||||||
|
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_INVALID_ARGUMENT,
|
||||||
|
rcl_wait_set_get_allocator(nullptr, &allocator_returned)) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_WAIT_SET_INVALID,
|
||||||
|
rcl_wait_set_get_allocator(&wait_set, &allocator_returned)) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
rcl_ret_t ret =
|
||||||
|
rcl_wait_set_init(&wait_set, 1, 1, 1, 1, 1, 0, context_ptr, rcl_get_default_allocator());
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(
|
||||||
|
RCL_RET_INVALID_ARGUMENT,
|
||||||
|
rcl_wait_set_get_allocator(&wait_set, nullptr)) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_wait_set_get_allocator(&wait_set, &allocator_returned));
|
||||||
|
EXPECT_TRUE(rcutils_allocator_is_valid(&allocator_returned));
|
||||||
|
|
||||||
|
ret = rcl_wait_set_fini(&wait_set);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue