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

[foxy backport] Add check to rcl_node_options_copy for invalid arg (#671) + add tests (#668) #697

Merged
merged 2 commits into from
Jun 24, 2020
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
4 changes: 4 additions & 0 deletions rcl/src/rcl/node_options.c
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,10 @@ rcl_node_options_copy(
RCL_SET_ERROR_MSG("Attempted to copy options into itself");
return RCL_RET_INVALID_ARGUMENT;
}
if (NULL != options_out->arguments.impl) {
RCL_SET_ERROR_MSG("Options out must be zero initialized");
return RCL_RET_INVALID_ARGUMENT;
}
options_out->domain_id = options->domain_id;
options_out->allocator = options->allocator;
options_out->use_global_arguments = options->use_global_arguments;
Expand Down
19 changes: 19 additions & 0 deletions rcl/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -326,6 +326,18 @@ rcl_add_custom_gtest(test_validate_enclave_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
SRCS rcl/test_validate_topic_name.cpp
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
Expand All @@ -352,6 +364,13 @@ rcl_add_custom_gtest(test_security
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(DIRECTORY ${test_resources_dir_name}
DESTINATION ${CMAKE_CURRENT_BINARY_DIR})
73 changes: 72 additions & 1 deletion rcl/test/rcl/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class TestClientFixture : public ::testing::Test
}
};

/* 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) {
rcl_ret_t ret;
Expand All @@ -82,6 +82,14 @@ TEST_F(TestClientFixture, test_client_nominal) {
test_msgs, srv, BasicTypes);
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
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(strcmp(rcl_client_get_service_name(&client), expected_topic_name), 0);
Expand Down Expand Up @@ -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);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
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);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error();
Expand Down Expand Up @@ -206,3 +216,64 @@ TEST_F(TestClientFixture, test_client_init_fini) {
EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string().str;
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, &not_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 changes: 34 additions & 0 deletions rcl/test/rcl/test_common.cpp
Original file line number Diff line number Diff line change
@@ -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 changes: 36 additions & 0 deletions rcl/test/rcl/test_domain_id.cpp
Original file line number Diff line number Diff line change
@@ -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 changes: 41 additions & 0 deletions rcl/test/rcl/test_localhost.cpp
Original file line number Diff line number Diff line change
@@ -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));
}
54 changes: 54 additions & 0 deletions rcl/test/rcl/test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -745,3 +745,57 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names) {
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, &not_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(&not_ini_options));
}

/* Tests special case node_options
*/
TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_options_fail) {
rcl_node_options_t prev_ini_options = rcl_node_get_default_options();
const char * argv[] = {"--ros-args"};
int argc = sizeof(argv) / sizeof(const char *);
EXPECT_EQ(
RCL_RET_OK,
rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &prev_ini_options.arguments));

rcl_node_options_t default_options = rcl_node_get_default_options();
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_node_options_copy(&default_options, &prev_ini_options));
}
Loading