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

[Backport Foxy] Increased code coverage and some fixes #848

Merged
merged 42 commits into from
Nov 2, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
42 commits
Select commit Hold shift + click to select a range
e0b92ef
Add tests for rcl package (#668)
Blast545 Jun 9, 2020
921c5ff
Add bad arguments tests for coverage (#698)
Blast545 Jul 3, 2020
3fa8af8
Add coverage tests for `rcl` (#703)
Blast545 Jul 7, 2020
8858fcc
Move rcl_remap_copy to public header (#709)
Blast545 Jul 16, 2020
f1d889d
Make public ini/fini rosout publisher (#704)
Blast545 Jul 20, 2020
608cbb6
Add remap needed null check (#711)
Blast545 Jul 20, 2020
12ead98
Make sure to call rcl_arguments_fini at the end of the test.
clalancette Jul 21, 2020
b334288
Reformat rmw_impl_id_check to call a testable function (#725)
Blast545 Jul 27, 2020
286de92
Add mock tests, publisher 95% coverage (#732)
Blast545 Aug 10, 2020
47327f8
Add missing calls to rcl_convert_rmw_ret_to_rcl_ret (#738)
Blast545 Aug 11, 2020
e485dae
Add deallocate calls to free strdup allocated memory (#737)
Blast545 Aug 11, 2020
c595ca1
Complete subscription API test coverage (#734)
hidmic Aug 12, 2020
f51f8e5
Fix bug error handling get_param_files (#743)
Blast545 Aug 13, 2020
364e1fb
Fix rcl package's logging API error specs and handling. (#746)
hidmic Aug 14, 2020
ad8b2b7
Fix allocation arguments copy (#748)
Blast545 Aug 18, 2020
44235ee
Complete rcl enclave validation API coverage. (#751)
hidmic Aug 19, 2020
cabc782
Added path_to_fail to mocking_utils in rcl
ahcorde Oct 30, 2020
12e104d
Clean up rcl_expand_topic_name() implementation. (#757)
hidmic Aug 19, 2020
f4a51b4
Add coverage tests 94% service.c (#756)
Blast545 Aug 20, 2020
99efabd
Extend rcl_expand_topic_name() API test coverage. (#758)
hidmic Aug 20, 2020
30a9681
Adding tests to arguments.c (#752)
Blast545 Aug 20, 2020
8ee5552
Zero initialize guard condition on failed init. (#760)
hidmic Aug 25, 2020
63842fd
Do not invalidate context before successful shutdown. (#761)
hidmic Aug 25, 2020
0c02c8d
Yield rcl_context_fini() error codes. (#763)
hidmic Aug 25, 2020
e79b900
Add fault injection macros to rcl functions (#727)
brawner Aug 25, 2020
1f9f627
Cleanup rcl_get_secure_root() implementation. (#762)
hidmic Aug 25, 2020
bfff4c1
Check rcutils_strdup() outcome immediately. (#768)
hidmic Aug 28, 2020
adfb2e9
Bump test coverage. (#764)
hidmic Aug 28, 2020
e2f6526
Fix wait allocation cleanup (#770)
Blast545 Aug 31, 2020
a72ae0a
Add coverage tests wait module (#769)
Blast545 Sep 1, 2020
7ee8e11
Fix rcl arguments' API memory leaks and bugs. (#778)
hidmic Sep 1, 2020
ece5251
Bump rcl arguments' API test coverage. (#777)
hidmic Sep 1, 2020
14d1784
Fixed log level in backported foxy tests
ahcorde Oct 30, 2020
8b9d9cc
calling fini functions to avoid memory leak (#791)
Sep 8, 2020
99c96ea
Fix that not to deallocate event impl in some failure case (#790)
Sep 8, 2020
f3a7318
Fix memory leak because of mock test (#800)
Sep 15, 2020
f9cea34
Make sure to check the return value of rcl APIs. (#838)
clalancette Oct 19, 2020
8d47d7c
Return OK when finalizing zero-initialized contexts (#842)
jacobperron Oct 28, 2020
6222bee
Zero initialize events an size_of_events members of rcl_wait_set_t (#…
jacobperron Oct 28, 2020
caf3a16
Make sure to always check return values. (#840)
clalancette Oct 29, 2020
488d54e
Add a semicolon to RCUTILS_LOGGING_AUTOINIT. (#816)
clalancette Oct 5, 2020
6ac4453
increase timeouts in test_services fixtures for Connext (#745)
dirk-thomas Aug 12, 2020
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/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,10 @@ ament_target_dependencies(${PROJECT_NAME}
target_compile_definitions(${PROJECT_NAME} PRIVATE "RCL_BUILDING_DLL")
rcl_set_symbol_visibility_hidden(${PROJECT_NAME} LANGUAGE "C")

if(BUILD_TESTING AND NOT RCUTILS_DISABLE_FAULT_INJECTION)
target_compile_definitions(${PROJECT_NAME} PUBLIC RCUTILS_ENABLE_FAULT_INJECTION)
endif()

install(
TARGETS ${PROJECT_NAME} EXPORT ${PROJECT_NAME}
ARCHIVE DESTINATION lib
Expand Down
3 changes: 2 additions & 1 deletion rcl/include/rcl/context.h
Original file line number Diff line number Diff line change
Expand Up @@ -154,8 +154,9 @@ rcl_get_zero_initialized_context(void);
/**
* The context to be finalized must have been previously initialized with
* `rcl_init()`, and then later invalidated with `rcl_shutdown()`.
* A zero-initialized context that has not been initialized can be finalized.
* If context is `NULL`, then `RCL_RET_INVALID_ARGUMENT` is returned.
* If context is zero-initialized, then `RCL_RET_INVALID_ARGUMENT` is returned.
* If context is zero-initialized, then `RCL_RET_OK` is returned.
* If context is initialized and valid (`rcl_shutdown()` was not called on it),
* then `RCL_RET_INVALID_ARGUMENT` is returned.
*
Expand Down
7 changes: 4 additions & 3 deletions rcl/include/rcl/logging.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ typedef rcutils_logging_output_handler_t rcl_logging_output_handler_t;
* \return `RCL_RET_OK` if successful, or
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
* \return `RCL_RET_ERR` if a general error occurs
* \return `RCL_RET_ERROR` if a general error occurs
*/
RCL_PUBLIC
RCL_WARN_UNUSED
Expand All @@ -74,8 +74,9 @@ rcl_logging_configure(
* \param allocator Used to allocate memory used by the logging system
* \param output_handler Output handler to be installed
* \return `RCL_RET_OK` if successful, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
* \return `RCL_RET_ERR` if a general error occurs
* \return `RCL_RET_ERROR` if a general error occurs
*/
RCL_PUBLIC
RCL_WARN_UNUSED
Expand All @@ -97,7 +98,7 @@ rcl_logging_configure_with_output_handler(
* Lock-Free | Yes
*
* \return `RCL_RET_OK` if successful.
* \return `RCL_RET_ERR` if a general error occurs
* \return `RCL_RET_ERROR` if a general error occurs
*/
RCL_PUBLIC
RCL_WARN_UNUSED
Expand Down
4 changes: 2 additions & 2 deletions rcl/include/rcl/logging_rosout.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ rcl_logging_rosout_fini();
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
*/
RCL_LOCAL
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_logging_rosout_init_publisher_for_node(
Expand All @@ -124,7 +124,7 @@ rcl_logging_rosout_init_publisher_for_node(
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
*/
RCL_LOCAL
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_logging_rosout_fini_publisher_for_node(
Expand Down
25 changes: 25 additions & 0 deletions rcl/include/rcl/remap.h
Original file line number Diff line number Diff line change
Expand Up @@ -247,6 +247,31 @@ rcl_remap_node_namespace(
rcl_allocator_t allocator,
char ** output_namespace);

/// Copy one remap structure into another.
/**
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[in] rule The structure to be copied.
* Its allocator is used to copy memory into the new structure.
* \param[out] rule_out A zero-initialized rcl_remap_t structure to be copied into.
* \return `RCL_RET_OK` if the structure was copied successfully, or
* \return `RCL_RET_INVALID_ARGUMENT` if any function arguments are invalid, or
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
*/
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_remap_copy(
const rcl_remap_t * rule,
rcl_remap_t * rule_out);

/// Reclaim resources held inside rcl_remap_t structure.
/**
* <hr>
Expand Down
35 changes: 35 additions & 0 deletions rcl/include/rcl/rmw_implementation_identifier_check.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
// 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.

#ifndef RCL__RMW_IMPLEMENTATION_IDENTIFIER_CHECK_H_
#define RCL__RMW_IMPLEMENTATION_IDENTIFIER_CHECK_H_

#ifdef __cplusplus
extern "C"
{
#endif

#include "rcl/visibility_control.h"

#define RMW_IMPLEMENTATION_ENV_VAR_NAME "RMW_IMPLEMENTATION"
#define RCL_ASSERT_RMW_ID_MATCHES_ENV_VAR_NAME "RCL_ASSERT_RMW_ID_MATCHES"

RCL_PUBLIC
rcl_ret_t rcl_rmw_implementation_identifier_check(void);

#ifdef __cplusplus
}
#endif

#endif // RCL__RMW_IMPLEMENTATION_IDENTIFIER_CHECK_H_
7 changes: 4 additions & 3 deletions rcl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,13 +25,14 @@
<test_depend>ament_cmake_pytest</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>rcpputils</test_depend>
<test_depend>rmw</test_depend>
<test_depend>rmw_implementation_cmake</test_depend>
<test_depend>launch</test_depend>
<test_depend>launch_testing</test_depend>
<test_depend>launch_testing_ament_cmake</test_depend>
<test_depend>mimick_vendor</test_depend>
<test_depend>osrf_testing_tools_cpp</test_depend>
<test_depend>rcpputils</test_depend>
<test_depend>rmw</test_depend>
<test_depend>rmw_implementation_cmake</test_depend>
<test_depend>test_msgs</test_depend>

<group_depend>rcl_logging_packages</group_depend>
Expand Down
87 changes: 50 additions & 37 deletions rcl/src/rcl/arguments.c
Original file line number Diff line number Diff line change
Expand Up @@ -93,10 +93,7 @@ rcl_arguments_get_param_files(
if (NULL == (*parameter_files)[i]) {
// deallocate allocated memory
for (int r = i; r >= 0; --r) {
if (NULL == (*parameter_files[r])) {
break;
}
allocator.deallocate((*parameter_files[r]), allocator.state);
allocator.deallocate((*parameter_files)[r], allocator.state);
}
allocator.deallocate((*parameter_files), allocator.state);
(*parameter_files) = NULL;
Expand Down Expand Up @@ -579,30 +576,36 @@ rcl_parse_arguments(
}

// Shrink remap_rules array to match number of successfully parsed rules
if (args_impl->num_remap_rules > 0) {
args_impl->remap_rules = rcutils_reallocf(
args_impl->remap_rules, sizeof(rcl_remap_t) * args_impl->num_remap_rules, &allocator);
if (NULL == args_impl->remap_rules) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
} else {
if (0 == args_impl->num_remap_rules) {
// No remap rules
allocator.deallocate(args_impl->remap_rules, allocator.state);
args_impl->remap_rules = NULL;
} else if (args_impl->num_remap_rules < argc) {
rcl_remap_t * new_remap_rules = allocator.reallocate(
args_impl->remap_rules,
sizeof(rcl_remap_t) * args_impl->num_remap_rules,
&allocator);
if (NULL == new_remap_rules) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
args_impl->remap_rules = new_remap_rules;
}

// Shrink Parameter files
if (0 == args_impl->num_param_files_args) {
allocator.deallocate(args_impl->parameter_files, allocator.state);
args_impl->parameter_files = NULL;
} else if (args_impl->num_param_files_args < argc) {
args_impl->parameter_files = rcutils_reallocf(
args_impl->parameter_files, sizeof(char *) * args_impl->num_param_files_args, &allocator);
if (NULL == args_impl->parameter_files) {
char ** new_parameter_files = allocator.reallocate(
args_impl->parameter_files,
sizeof(char *) * args_impl->num_param_files_args,
&allocator);
if (NULL == new_parameter_files) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
args_impl->parameter_files = new_parameter_files;
}

// Drop parameter overrides if none was found.
Expand Down Expand Up @@ -786,6 +789,9 @@ rcl_arguments_copy(
const rcl_arguments_t * args,
rcl_arguments_t * args_out)
{
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);

RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args_out, RCL_RET_INVALID_ARGUMENT);
Expand Down Expand Up @@ -843,7 +849,6 @@ rcl_arguments_copy(
}
return RCL_RET_BAD_ALLOC;
}
args_out->impl->num_remap_rules = args->impl->num_remap_rules;
for (int i = 0; i < args->impl->num_remap_rules; ++i) {
args_out->impl->remap_rules[i] = rcl_get_zero_initialized_remap();
ret = rcl_remap_copy(
Expand All @@ -854,6 +859,7 @@ rcl_arguments_copy(
}
return ret;
}
++(args_out->impl->num_remap_rules);
}
}

Expand All @@ -865,15 +871,14 @@ rcl_arguments_copy(

// Copy parameter files
if (args->impl->num_param_files_args) {
args_out->impl->parameter_files = allocator.allocate(
sizeof(char *) * args->impl->num_param_files_args, allocator.state);
args_out->impl->parameter_files = allocator.zero_allocate(
args->impl->num_param_files_args, sizeof(char *), allocator.state);
if (NULL == args_out->impl->parameter_files) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
}
return RCL_RET_BAD_ALLOC;
}
args_out->impl->num_param_files_args = args->impl->num_param_files_args;
for (int i = 0; i < args->impl->num_param_files_args; ++i) {
args_out->impl->parameter_files[i] =
rcutils_strdup(args->impl->parameter_files[i], allocator);
Expand All @@ -883,6 +888,7 @@ rcl_arguments_copy(
}
return RCL_RET_BAD_ALLOC;
}
++(args_out->impl->num_param_files_args);
}
}
char * enclave_copy = rcutils_strdup(args->impl->enclave, allocator);
Expand Down Expand Up @@ -1619,9 +1625,8 @@ _rcl_parse_remap_rule(
RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(output_rule, RCL_RET_INVALID_ARGUMENT);

rcl_ret_t ret;

output_rule->impl = allocator.allocate(sizeof(rcl_remap_impl_t), allocator.state);
output_rule->impl =
allocator.allocate(sizeof(rcl_remap_impl_t), allocator.state);
if (NULL == output_rule->impl) {
return RCL_RET_BAD_ALLOC;
}
Expand All @@ -1632,25 +1637,31 @@ _rcl_parse_remap_rule(
output_rule->impl->replacement = NULL;

rcl_lexer_lookahead2_t lex_lookahead = rcl_get_zero_initialized_lexer_lookahead2();
rcl_ret_t ret = rcl_lexer_lookahead2_init(&lex_lookahead, arg, allocator);

ret = rcl_lexer_lookahead2_init(&lex_lookahead, arg, allocator);
if (RCL_RET_OK != ret) {
return ret;
}

ret = _rcl_parse_remap_begin_remap_rule(&lex_lookahead, output_rule);
if (RCL_RET_OK == ret) {
ret = _rcl_parse_remap_begin_remap_rule(&lex_lookahead, output_rule);

if (RCL_RET_OK != ret) {
// cleanup stuff, but return the original error code
if (RCL_RET_OK != rcl_remap_fini(output_rule)) {
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to fini remap rule after error occurred");
}
if (RCL_RET_OK != rcl_lexer_lookahead2_fini(&lex_lookahead)) {
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to fini lookahead2 after error occurred");
rcl_ret_t fini_ret = rcl_lexer_lookahead2_fini(&lex_lookahead);
if (RCL_RET_OK != ret) {
if (RCL_RET_OK != fini_ret) {
RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Failed to fini lookahead2 after error occurred");
}
} else {
if (RCL_RET_OK == fini_ret) {
return RCL_RET_OK;
}
ret = fini_ret;
}
} else {
ret = rcl_lexer_lookahead2_fini(&lex_lookahead);
}

// cleanup output rule but keep first error return code
if (RCL_RET_OK != rcl_remap_fini(output_rule)) {
RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Failed to fini remap rule after error occurred");
}

return ret;
}

Expand Down Expand Up @@ -1747,6 +1758,8 @@ _rcl_parse_param_file(
return RCL_RET_BAD_ALLOC;
}
if (!rcl_parse_yaml_file(*param_file, params)) {
allocator.deallocate(*param_file, allocator.state);
*param_file = NULL;
// Error message already set.
return RCL_RET_ERROR;
}
Expand Down
5 changes: 5 additions & 0 deletions rcl/src/rcl/client.c
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ extern "C"
#include "rcl/expand_topic_name.h"
#include "rcl/remap.h"
#include "rcutils/logging_macros.h"
#include "rcutils/macros.h"
#include "rcutils/stdatomic_helper.h"
#include "rmw/error_handling.h"
#include "rmw/rmw.h"
Expand Down Expand Up @@ -206,6 +207,10 @@ rcl_client_init(
rcl_ret_t
rcl_client_fini(rcl_client_t * client, rcl_node_t * node)
{
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_NODE_INVALID);
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);

RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing client");
rcl_ret_t result = RCL_RET_OK;
RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT);
Expand Down
Loading