-
Notifications
You must be signed in to change notification settings - Fork 411
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
Increase coverage of node_interfaces, including with mocking rcl errors #1322
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -21,6 +21,11 @@ | |
#include "rclcpp/node.hpp" | ||
#include "rclcpp/node_interfaces/node_base.hpp" | ||
#include "rclcpp/rclcpp.hpp" | ||
#include "rmw/validate_namespace.h" | ||
#include "rmw/validate_node_name.h" | ||
|
||
#include "../../mocking_utils/patch.hpp" | ||
#include "../../utils/rclcpp_gtest_macros.hpp" | ||
|
||
class TestNodeBase : public ::testing::Test | ||
{ | ||
|
@@ -36,6 +41,12 @@ class TestNodeBase : public ::testing::Test | |
} | ||
}; | ||
|
||
// Required for mocking_utils below | ||
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, ==) | ||
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, !=) | ||
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, <) | ||
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, >) | ||
|
||
TEST_F(TestNodeBase, construct_from_node) | ||
{ | ||
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns"); | ||
|
@@ -58,3 +69,125 @@ TEST_F(TestNodeBase, construct_from_node) | |
EXPECT_NE(nullptr, const_node_base->get_rcl_node_handle()); | ||
EXPECT_NE(nullptr, const_node_base->get_shared_rcl_node_handle()); | ||
} | ||
|
||
TEST_F(TestNodeBase, construct_destruct_rcl_guard_condition_init_error) { | ||
auto mock = mocking_utils::patch_and_return( | ||
"lib:rclcpp", rcl_guard_condition_init, RCL_RET_ERROR); | ||
EXPECT_THROW( | ||
std::make_shared<rclcpp::Node>("node", "ns").reset(), | ||
rclcpp::exceptions::RCLError); | ||
} | ||
|
||
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_error) { | ||
auto mock_node_init = mocking_utils::patch_and_return( | ||
"lib:rclcpp", rcl_node_init, RCL_RET_ERROR); | ||
|
||
// This function is called only if rcl_node_init fails, so both mocked functions are required | ||
// This just logs an error, so behavior shouldn't change | ||
auto mock_guard_condition_fini = mocking_utils::inject_on_return( | ||
"lib:rclcpp", rcl_guard_condition_fini, RCL_RET_ERROR); | ||
|
||
EXPECT_THROW( | ||
std::make_shared<rclcpp::Node>("node", "ns").reset(), | ||
rclcpp::exceptions::RCLError); | ||
} | ||
|
||
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_node_name) { | ||
auto mock_node_init = mocking_utils::patch_and_return( | ||
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAME); | ||
|
||
// `rmw_validate_node_name` is only called if `rcl_node_init` returns INVALID_NAME | ||
auto mock_validate_node_name = mocking_utils::patch_and_return( | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. If both mocks cause the same error (invalid node), I imagine these should be tested in different blocks, right? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Or both error mocks are needed to cause the condition? if this is the case please add a comment saying that. Same for the tests below that are 2 mocks and 1 error. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. These two-mock cases all require |
||
"lib:rclcpp", rmw_validate_node_name, RMW_RET_ERROR); | ||
|
||
EXPECT_THROW( | ||
std::make_shared<rclcpp::Node>("node", "ns").reset(), | ||
rclcpp::exceptions::RCLError); | ||
} | ||
|
||
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_node_name_invalid_argument) { | ||
auto mock_node_init = mocking_utils::patch_and_return( | ||
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAME); | ||
|
||
// `rmw_validate_node_name` is only called if `rcl_node_init` returns INVALID_NAME | ||
auto mock_validate_node_name = mocking_utils::patch_and_return( | ||
"lib:rclcpp", rmw_validate_node_name, RMW_RET_INVALID_ARGUMENT); | ||
|
||
EXPECT_THROW( | ||
std::make_shared<rclcpp::Node>("node", "ns").reset(), | ||
rclcpp::exceptions::RCLInvalidArgument); | ||
} | ||
|
||
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_node_name_valid_rmw_node_name) { | ||
auto mock_node_init = mocking_utils::patch_and_return( | ||
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAME); | ||
|
||
// `rmw_validate_node_name` is only called if `rcl_node_init` returns INVALID_NAME | ||
auto mock = mocking_utils::patch( | ||
"lib:rclcpp", rmw_validate_node_name, [](const char *, int * validation_result, size_t *) | ||
{ | ||
*validation_result = RMW_NODE_NAME_VALID; | ||
return RMW_RET_OK; | ||
}); | ||
|
||
RCLCPP_EXPECT_THROW_EQ( | ||
std::make_shared<rclcpp::Node>("node", "ns").reset(), | ||
std::runtime_error("valid rmw node name but invalid rcl node name")); | ||
} | ||
|
||
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_namespace) { | ||
auto mock_node_init = mocking_utils::patch_and_return( | ||
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAMESPACE); | ||
|
||
// `rmw_validate_namespace` is only called if `rcl_node_init` returns INVALID_NAMESPACE | ||
auto mock_validate_namespace = mocking_utils::patch_and_return( | ||
"lib:rclcpp", rmw_validate_namespace, RMW_RET_ERROR); | ||
|
||
EXPECT_THROW( | ||
std::make_shared<rclcpp::Node>("node", "ns").reset(), | ||
rclcpp::exceptions::RCLError); | ||
} | ||
|
||
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_namespace_rmw_invalid_argument) { | ||
auto mock_node_init = mocking_utils::patch_and_return( | ||
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAMESPACE); | ||
|
||
// `rmw_validate_namespace` is only called if `rcl_node_init` returns INVALID_NAMESPACE | ||
auto mock_validate_namespace = mocking_utils::patch_and_return( | ||
"lib:rclcpp", rmw_validate_namespace, RMW_RET_INVALID_ARGUMENT); | ||
|
||
EXPECT_THROW( | ||
std::make_shared<rclcpp::Node>("node", "ns").reset(), | ||
rclcpp::exceptions::RCLInvalidArgument); | ||
} | ||
|
||
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_namespace_valid_rmw_namespace) { | ||
auto mock_node_init = mocking_utils::patch_and_return( | ||
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAMESPACE); | ||
|
||
// `rmw_validate_namespace` is only called if `rcl_node_init` returns INVALID_NAMESPACE | ||
auto mock = mocking_utils::patch( | ||
"lib:rclcpp", rmw_validate_namespace, [](const char *, int * validation_result, size_t *) | ||
{ | ||
*validation_result = RMW_NAMESPACE_VALID; | ||
return RMW_RET_OK; | ||
}); | ||
|
||
RCLCPP_EXPECT_THROW_EQ( | ||
std::make_shared<rclcpp::Node>("node", "ns").reset(), | ||
std::runtime_error("valid rmw node namespace but invalid rcl node namespace")); | ||
} | ||
|
||
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_fini_error) { | ||
auto mock_node_fini = mocking_utils::inject_on_return( | ||
"lib:rclcpp", rcl_node_fini, RCL_RET_ERROR); | ||
|
||
EXPECT_NO_THROW(std::make_shared<rclcpp::Node>("node", "ns").reset()); | ||
} | ||
|
||
TEST_F(TestNodeBase, construct_destruct_rcl_guard_condition_fini_error) { | ||
auto mock_node_fini = mocking_utils::inject_on_return( | ||
"lib:rclcpp", rcl_guard_condition_fini, RCL_RET_ERROR); | ||
|
||
EXPECT_NO_THROW(std::make_shared<rclcpp::Node>("node", "ns").reset()); | ||
} |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Could this mock be tested in its own block? If the
rcl_node_init
is changed to be executed first then the lines covered by this mock won't be triggeredThere was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
rcl_guard_condition_fini
is only called ifrcl_node_init
fails, so I don't think so.