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

Add coverage tests for rcl #703

Merged
merged 22 commits into from
Jul 7, 2020
Merged
Show file tree
Hide file tree
Changes from 13 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: 3 additions & 1 deletion rcl/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -170,14 +170,16 @@ function(test_target_function)
SRCS rcl/test_arguments.cpp
ENV ${rmw_implementation_env_var}
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/
LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools
AMENT_DEPENDENCIES "osrf_testing_tools_cpp" "rcpputils"
)

rcl_add_custom_gtest(test_remap${target_suffix}
SRCS rcl/test_remap.cpp
SRCS rcl/test_remap.cpp ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/remap.c
ENV ${rmw_implementation_env_var}
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/
LIBRARIES ${PROJECT_NAME}
AMENT_DEPENDENCIES "osrf_testing_tools_cpp"
)
Expand Down
89 changes: 89 additions & 0 deletions rcl/test/rcl/test_arguments.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,9 @@

#include "rcl_yaml_param_parser/parser.h"

#include "./allocator_testing_utils.h"
#include "./arguments_impl.h"

#ifdef RMW_IMPLEMENTATION
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
Expand Down Expand Up @@ -281,6 +284,60 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_args) {
rcl_reset_error();
}

TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_negative_args) {
int argc = -1;
Blast545 marked this conversation as resolved.
Show resolved Hide resolved
const char * argv[] = {"process_name"};
Blast545 marked this conversation as resolved.
Show resolved Hide resolved
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
}

TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_parse_args) {
const char * argv[] = {"process_name"};
int argc = sizeof(argv) / sizeof(const char *);
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_allocator_t bad_alloc = get_failing_allocator();
rcl_ret_t ret = rcl_parse_arguments(argc, argv, bad_alloc, &parsed_args);
EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string().str;
rcl_reset_error();
}

TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_unparse_args) {
const char * argv[] = {
"process_name", "--ros-args", "/foo/bar:=", "-r", "bar:=/fiz/buz", "}bar:=fiz", "--", "arg"};
int argc = sizeof(argv) / sizeof(const char *);
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_allocator_t bad_alloc = get_failing_allocator();
rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
Blast545 marked this conversation as resolved.
Show resolved Hide resolved
EXPECT_EQ(2, rcl_arguments_get_count_unparsed(&parsed_args));

int * actual_unparsed = NULL;
EXPECT_EQ(
RCL_RET_BAD_ALLOC, rcl_arguments_get_unparsed(&parsed_args, bad_alloc, &actual_unparsed));
rcl_reset_error();
EXPECT_EQ(
RCL_RET_BAD_ALLOC, rcl_arguments_get_unparsed_ros(&parsed_args, bad_alloc, &actual_unparsed));
rcl_reset_error();
Blast545 marked this conversation as resolved.
Show resolved Hide resolved
}

TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_params_get_counts) {
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
EXPECT_EQ(-1, rcl_arguments_get_count_unparsed(nullptr));
rcl_reset_error();
EXPECT_EQ(-1, rcl_arguments_get_count_unparsed_ros(nullptr));
rcl_reset_error();
EXPECT_EQ(-1, rcl_arguments_get_param_files_count(nullptr));
rcl_reset_error();
EXPECT_EQ(-1, rcl_arguments_get_count_unparsed(&parsed_args));
rcl_reset_error();
EXPECT_EQ(-1, rcl_arguments_get_count_unparsed_ros(&parsed_args));
rcl_reset_error();
EXPECT_EQ(-1, rcl_arguments_get_param_files_count(&parsed_args));
rcl_reset_error();
}

TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_args_output) {
const char * argv[] = {"process_name"};
int argc = sizeof(argv) / sizeof(const char *);
Expand Down Expand Up @@ -402,6 +459,11 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy) {
ret = rcl_arguments_copy(&parsed_args, &copied_args);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;

// Can't copy to non empty
ret = rcl_arguments_copy(&parsed_args, &copied_args);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();

EXPECT_UNPARSED(parsed_args, 0, 8);
EXPECT_UNPARSED_ROS(parsed_args, 2);
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
Expand All @@ -411,6 +473,27 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy) {
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&copied_args));
}

TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_bad_alloc) {
const char * argv[] = {"process_name", "--ros-args", "/foo/bar:="};
int argc = sizeof(argv) / sizeof(const char *);
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_ret_t ret;

ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;

rcl_arguments_t copied_args = rcl_get_zero_initialized_arguments();
rcl_allocator_t bad_alloc = get_failing_allocator();
rcl_allocator_t * saved_alloc = &parsed_args.impl->allocator;
Blast545 marked this conversation as resolved.
Show resolved Hide resolved
parsed_args.impl->allocator = bad_alloc;
ret = rcl_arguments_copy(&parsed_args, &copied_args);
EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string().str;
rcl_reset_error();
parsed_args.impl->allocator = *saved_alloc;

EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
Blast545 marked this conversation as resolved.
Show resolved Hide resolved
}

TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_no_ros_args) {
const char * argv[] = {"process_name", "--ros-args", "--", "arg", "--ros-args"};
int argc = sizeof(argv) / sizeof(const char *);
Expand Down Expand Up @@ -565,6 +648,12 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_remove_ros_
argv, &parsed_args, zero_initialized_allocator, &nonros_argc, &nonros_argv));
rcl_reset_error();

rcl_allocator_t bad_alloc = get_failing_allocator();
EXPECT_EQ(
RCL_RET_BAD_ALLOC, rcl_remove_ros_arguments(
argv, &parsed_args, bad_alloc, &nonros_argc, &nonros_argv));
rcl_reset_error();

EXPECT_EQ(
RCL_RET_INVALID_ARGUMENT, rcl_remove_ros_arguments(
argv, &parsed_args, default_allocator, NULL, &nonros_argv));
Expand Down
195 changes: 193 additions & 2 deletions rcl/test/rcl/test_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ TEST_F(
rcl_allocator_t allocator = rcl_get_default_allocator();
rcl_allocator_t zero_allocator = static_cast<rcl_allocator_t>(
rcutils_get_zero_initialized_allocator());
rcl_names_and_types_t tnat {};
rcl_names_and_types_t tnat = rcl_get_zero_initialized_names_and_types();
rcl_node_t zero_node = rcl_get_zero_initialized_node();
// invalid node
ret = rcl_get_topic_names_and_types(nullptr, &allocator, false, &tnat);
Expand All @@ -172,6 +172,11 @@ TEST_F(
ret = rcl_get_topic_names_and_types(this->node_ptr, &allocator, false, nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
tnat.names.size = 1;
ret = rcl_get_topic_names_and_types(this->node_ptr, &allocator, false, &tnat);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
tnat.names.size = 0;
// invalid argument to rcl_destroy_topic_names_and_types
ret = rcl_names_and_types_fini(nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
Expand All @@ -195,7 +200,7 @@ TEST_F(
rcl_allocator_t allocator = rcl_get_default_allocator();
rcl_allocator_t zero_allocator = static_cast<rcl_allocator_t>(
rcutils_get_zero_initialized_allocator());
rcl_names_and_types_t tnat {};
rcl_names_and_types_t tnat = rcl_get_zero_initialized_names_and_types();
rcl_node_t zero_node = rcl_get_zero_initialized_node();
// invalid node
ret = rcl_get_service_names_and_types(nullptr, &allocator, &tnat);
Expand All @@ -218,6 +223,11 @@ TEST_F(
ret = rcl_get_service_names_and_types(this->node_ptr, &allocator, nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
tnat.names.size = 1;
ret = rcl_get_service_names_and_types(this->node_ptr, &allocator, &tnat);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
tnat.names.size = 0;
// invalid argument to rcl_destroy_service_names_and_types
ret = rcl_names_and_types_fini(nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
Expand Down Expand Up @@ -334,6 +344,12 @@ TEST_F(
this->node_ptr, &allocator, false, this->test_graph_node_name, "", nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
nat.names.size = 1;
ret = rcl_get_publisher_names_and_types_by_node(
this->node_ptr, &allocator, false, this->test_graph_node_name, "", &nat);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
nat.names.size = 0;
// unknown node name
ret = rcl_get_publisher_names_and_types_by_node(
this->node_ptr, &allocator, false, unknown_node_name, "", &nat);
Expand Down Expand Up @@ -419,6 +435,12 @@ TEST_F(
this->node_ptr, &allocator, false, this->test_graph_node_name, "", nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
nat.names.size = 1;
ret = rcl_get_subscriber_names_and_types_by_node(
this->node_ptr, &allocator, false, this->test_graph_node_name, "", &nat);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
nat.names.size = 0;
// unknown node name
ret = rcl_get_subscriber_names_and_types_by_node(
this->node_ptr, &allocator, false, unknown_node_name, "", &nat);
Expand Down Expand Up @@ -501,6 +523,12 @@ TEST_F(
this->node_ptr, &allocator, this->test_graph_node_name, "", nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
nat.names.size = 1;
ret = rcl_get_service_names_and_types_by_node(
this->node_ptr, &allocator, this->test_graph_node_name, "", &nat);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
nat.names.size = 0;
// unknown node name
ret = rcl_get_service_names_and_types_by_node(
this->node_ptr, &allocator, unknown_node_name, "", &nat);
Expand Down Expand Up @@ -584,6 +612,12 @@ TEST_F(
this->node_ptr, &allocator, this->test_graph_node_name, "", nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
nat.names.size = 1;
ret = rcl_get_client_names_and_types_by_node(
this->node_ptr, &allocator, this->test_graph_node_name, "", &nat);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error();
nat.names.size = 0;
// unknown node name
ret = rcl_get_client_names_and_types_by_node(
this->node_ptr, &allocator, unknown_node_name, "", &nat);
Expand Down Expand Up @@ -1354,3 +1388,160 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_
wait_for_service_state_to_change(false, is_available);
ASSERT_FALSE(is_available);
}

/* Test passing invalid params to server_is_available
*/
TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_server_available) {
// 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, srv, BasicTypes);
const char * service_name = "/service_test_rcl_service_server_is_available";
rcl_client_options_t client_options = rcl_client_get_default_options();
rcl_ret_t ret = rcl_client_init(&client, this->node_ptr, ts, service_name, &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;
});
// Check, knowing there is no service server (created by us at least).
bool is_available;
ret = rcl_service_server_is_available(this->node_ptr, &client, &is_available);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ASSERT_FALSE(is_available);

ret = rcl_service_server_is_available(nullptr, &client, &is_available);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret);
rcl_reset_error();
rcl_node_t not_init_node = rcl_get_zero_initialized_node();
ret = rcl_service_server_is_available(&not_init_node, &client, &is_available);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret);
rcl_reset_error();
}

/* Test passing invalid params to get_node_names functions
*/
TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) {
rcutils_string_array_t node_names = rcutils_get_zero_initialized_string_array();
rcutils_string_array_t node_namespaces = rcutils_get_zero_initialized_string_array();

rcutils_string_array_t node_names_2 = rcutils_get_zero_initialized_string_array();
rcutils_string_array_t node_namespaces_2 = rcutils_get_zero_initialized_string_array();
rcutils_string_array_t node_enclaves = rcutils_get_zero_initialized_string_array();
rcl_ret_t ret = RCL_RET_OK;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
ret = rcutils_string_array_fini(&node_names);
EXPECT_EQ(RCUTILS_RET_OK, ret);
ret = rcutils_string_array_fini(&node_namespaces);
EXPECT_EQ(RCUTILS_RET_OK, ret);
ret = rcutils_string_array_fini(&node_enclaves);
EXPECT_EQ(RCUTILS_RET_OK, ret);
});
rcl_allocator_t allocator = rcl_get_default_allocator();

ret = rcl_get_node_names(nullptr, allocator, &node_names, &node_namespaces);
Blast545 marked this conversation as resolved.
Show resolved Hide resolved
EXPECT_EQ(RCL_RET_NODE_INVALID, ret);
rcl_reset_error();
ret = rcl_get_node_names_with_enclaves(
nullptr, allocator, &node_names, &node_namespaces, &node_enclaves);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret);
rcl_reset_error();

rcl_node_t not_init_node = rcl_get_zero_initialized_node();
ret = rcl_get_node_names(&not_init_node, allocator, &node_names, &node_namespaces);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret);
rcl_reset_error();
ret = rcl_get_node_names_with_enclaves(
&not_init_node, allocator, &node_names, &node_namespaces, &node_enclaves);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret);
rcl_reset_error();

ret = rcl_get_node_names(this->node_ptr, allocator, nullptr, &node_namespaces);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
ret = rcl_get_node_names_with_enclaves(
this->node_ptr, allocator, nullptr, &node_namespaces, &node_enclaves);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
rcl_reset_error();

ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
ret = rcl_get_node_names_with_enclaves(
this->node_ptr, allocator, &node_names, nullptr, &node_enclaves);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
rcl_reset_error();

ret = rcl_get_node_names_with_enclaves(
this->node_ptr, allocator, &node_names, &node_namespaces, nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
rcl_reset_error();

node_names.size = 1;
ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
ret = rcl_get_node_names_with_enclaves(
this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
rcl_reset_error();
node_names.size = 0;

ret = rcutils_string_array_init(&node_names, 1, &allocator);
EXPECT_EQ(RCL_RET_OK, ret);
node_names.size = 0;
ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
ret = rcl_get_node_names_with_enclaves(
this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
rcl_reset_error();
node_names.size = 1;
ret = rcutils_string_array_fini(&node_names);
EXPECT_EQ(RCL_RET_OK, ret);

node_namespaces.size = 1;
ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
ret = rcl_get_node_names_with_enclaves(
this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
rcl_reset_error();
node_namespaces.size = 0;

ret = rcutils_string_array_init(&node_namespaces, 1, &allocator);
EXPECT_EQ(RCL_RET_OK, ret);
node_namespaces.size = 0;
ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
ret = rcl_get_node_names_with_enclaves(
this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
rcl_reset_error();
node_namespaces.size = 1;
ret = rcutils_string_array_fini(&node_namespaces);
EXPECT_EQ(RCL_RET_OK, ret);

node_enclaves.size = 1;
ret = rcl_get_node_names_with_enclaves(
this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
rcl_reset_error();
node_enclaves.size = 0;

ret = rcutils_string_array_init(&node_enclaves, 1, &allocator);
EXPECT_EQ(RCL_RET_OK, ret);
node_enclaves.size = 0;
ret = rcl_get_node_names_with_enclaves(
this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
rcl_reset_error();
node_enclaves.size = 1;
ret = rcutils_string_array_fini(&node_enclaves);
EXPECT_EQ(RCL_RET_OK, ret);

// Expected usage
ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces);
EXPECT_EQ(RCL_RET_OK, ret);
ret = rcl_get_node_names_with_enclaves(
this->node_ptr, allocator, &node_names_2, &node_namespaces_2, &node_enclaves);
EXPECT_EQ(RCL_RET_OK, ret);
}
Loading