Skip to content

Commit

Permalink
Add tests ini/fini error context
Browse files Browse the repository at this point in the history
Signed-off-by: Jorge Perez <jjperez@ekumenlabs.com>
  • Loading branch information
Blast545 committed Sep 18, 2020
1 parent d1e08e4 commit ab39863
Showing 1 changed file with 56 additions and 0 deletions.
56 changes: 56 additions & 0 deletions rclcpp/test/rclcpp/test_utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,9 @@
#include <string>
#include <memory>

#include "rcl/init.h"
#include "rcl/logging.h"

#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/utilities.hpp"
Expand Down Expand Up @@ -154,3 +157,56 @@ TEST(TestUtilities, test_context_release_interrupt_guard_condition) {

rclcpp::shutdown(context1);
}


TEST(TestUtilities, test_context_init_shutdown_fails) {
auto context = std::make_shared<rclcpp::contexts::DefaultContext>();

{
auto context_fail_init = std::make_shared<rclcpp::contexts::DefaultContext>();
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_init, RCL_RET_ERROR);
EXPECT_THROW(context_fail_init->init(0, nullptr), rclcpp::exceptions::RCLError);
}

{
auto context_fail_init = std::make_shared<rclcpp::contexts::DefaultContext>();
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_logging_configure_with_output_handler, RCL_RET_ERROR);
EXPECT_THROW(context_fail_init->init(0, nullptr), rclcpp::exceptions::RCLError);
}

{
context->init(0, nullptr);
auto mock = mocking_utils::inject_on_return(
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
// This will log a message, no throw expected
EXPECT_NO_THROW(context->shutdown(""));
}

{
context->init(0, nullptr);
auto mock = mocking_utils::inject_on_return(
"lib:rclcpp", rcl_shutdown, RCL_RET_ERROR);
EXPECT_THROW(context->shutdown(""), rclcpp::exceptions::RCLError);
}

{
context->init(0, nullptr);
auto mock = mocking_utils::inject_on_return(
"lib:rclcpp", rcl_logging_fini, RCL_RET_ERROR);
// This will log a message, no throw expected
EXPECT_NO_THROW(context->shutdown(""));
}

{
auto context_to_destroy = std::make_shared<rclcpp::contexts::DefaultContext>();
auto mock = mocking_utils::inject_on_return(
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
// This will log a message, no throw expected
EXPECT_NO_THROW(
{
// context_to_destroy.~rclcpp::Context();
});
}
}

0 comments on commit ab39863

Please sign in to comment.