Increase coverage rclcpp_action to 95% (#1290)
* Increase coverage rclcpp_action to 95% Signed-off-by: Stephen Brawner <brawner@gmail.com> * PR fixup Signed-off-by: Stephen Brawner <brawner@gmail.com> * Address PR Feedback Signed-off-by: Stephen Brawner <brawner@gmail.com> * Rebase onto #1311 Signed-off-by: Stephen Brawner <brawner@gmail.com> * rcutils test depend Signed-off-by: Stephen Brawner <brawner@gmail.com> * Cleaning up Signed-off-by: Stephen Brawner <brawner@gmail.com>
This commit is contained in:
parent
43df9eff37
commit
730e99b742
6 changed files with 1062 additions and 23 deletions
|
@ -15,6 +15,7 @@
|
|||
#include <rclcpp/exceptions.hpp>
|
||||
#include <rclcpp/node.hpp>
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <rclcpp/scope_exit.hpp>
|
||||
#include <test_msgs/action/fibonacci.hpp>
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
|
@ -22,8 +23,11 @@
|
|||
#include <memory>
|
||||
#include <vector>
|
||||
|
||||
#include "rcl_action/action_server.h"
|
||||
#include "rcl_action/wait.h"
|
||||
#include "rclcpp_action/create_server.hpp"
|
||||
#include "rclcpp_action/server.hpp"
|
||||
#include "./mocking_utils/patch.hpp"
|
||||
|
||||
using Fibonacci = test_msgs::action::Fibonacci;
|
||||
using CancelResponse = typename Fibonacci::Impl::CancelGoalService::Response;
|
||||
|
@ -37,8 +41,15 @@ protected:
|
|||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
static void TearDownTestCase()
|
||||
{
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
|
||||
std::shared_ptr<Fibonacci::Impl::SendGoalService::Request>
|
||||
send_goal_request(rclcpp::Node::SharedPtr node, GoalUUID uuid)
|
||||
send_goal_request(
|
||||
rclcpp::Node::SharedPtr node, GoalUUID uuid,
|
||||
std::chrono::milliseconds timeout = std::chrono::milliseconds(-1))
|
||||
{
|
||||
auto client = node->create_client<Fibonacci::Impl::SendGoalService>(
|
||||
"fibonacci/_action/send_goal");
|
||||
|
@ -48,17 +59,20 @@ protected:
|
|||
auto request = std::make_shared<Fibonacci::Impl::SendGoalService::Request>();
|
||||
request->goal_id.uuid = uuid;
|
||||
auto future = client->async_send_request(request);
|
||||
if (
|
||||
rclcpp::FutureReturnCode::SUCCESS !=
|
||||
rclcpp::spin_until_future_complete(node, future))
|
||||
{
|
||||
auto return_code = rclcpp::spin_until_future_complete(node, future, timeout);
|
||||
if (rclcpp::FutureReturnCode::SUCCESS == return_code) {
|
||||
return request;
|
||||
} else if (rclcpp::FutureReturnCode::TIMEOUT == return_code) {
|
||||
throw std::runtime_error("send goal future timed out");
|
||||
} else {
|
||||
throw std::runtime_error("send goal future didn't complete succesfully");
|
||||
}
|
||||
return request;
|
||||
}
|
||||
|
||||
CancelResponse::SharedPtr
|
||||
send_cancel_request(rclcpp::Node::SharedPtr node, GoalUUID uuid)
|
||||
send_cancel_request(
|
||||
rclcpp::Node::SharedPtr node, GoalUUID uuid,
|
||||
std::chrono::milliseconds timeout = std::chrono::milliseconds(-1))
|
||||
{
|
||||
auto cancel_client = node->create_client<Fibonacci::Impl::CancelGoalService>(
|
||||
"fibonacci/_action/cancel_goal");
|
||||
|
@ -68,13 +82,14 @@ protected:
|
|||
auto request = std::make_shared<Fibonacci::Impl::CancelGoalService::Request>();
|
||||
request->goal_info.goal_id.uuid = uuid;
|
||||
auto future = cancel_client->async_send_request(request);
|
||||
if (
|
||||
rclcpp::FutureReturnCode::SUCCESS !=
|
||||
rclcpp::spin_until_future_complete(node, future))
|
||||
{
|
||||
throw std::runtime_error("cancel goal future didn't complete succesfully");
|
||||
auto return_code = rclcpp::spin_until_future_complete(node, future, timeout);
|
||||
if (rclcpp::FutureReturnCode::SUCCESS == return_code) {
|
||||
return future.get();
|
||||
} else if (rclcpp::FutureReturnCode::TIMEOUT == return_code) {
|
||||
throw std::runtime_error("cancel request future timed out");
|
||||
} else {
|
||||
throw std::runtime_error("cancel request future didn't complete succesfully");
|
||||
}
|
||||
return future.get();
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -146,6 +161,50 @@ TEST_F(TestServer, construction_and_destruction_callback_group)
|
|||
group));
|
||||
}
|
||||
|
||||
TEST_F(TestServer, construction_and_destruction_server_init_error)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_server_init, RCL_RET_ERROR);
|
||||
auto node = std::make_shared<rclcpp::Node>("construct_node", "/rclcpp_action/construct");
|
||||
|
||||
EXPECT_THROW(
|
||||
{
|
||||
using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>;
|
||||
auto as = rclcpp_action::create_server<Fibonacci>(
|
||||
node, "fibonacci",
|
||||
[](const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>) {
|
||||
return rclcpp_action::GoalResponse::REJECT;
|
||||
},
|
||||
[](std::shared_ptr<GoalHandle>) {
|
||||
return rclcpp_action::CancelResponse::REJECT;
|
||||
},
|
||||
[](std::shared_ptr<GoalHandle>) {});
|
||||
(void)as;
|
||||
}, rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestServer, construction_and_destruction_wait_set_error)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_server_wait_set_get_num_entities, RCL_RET_ERROR);
|
||||
auto node = std::make_shared<rclcpp::Node>("construct_node", "/rclcpp_action/construct");
|
||||
|
||||
EXPECT_THROW(
|
||||
{
|
||||
using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>;
|
||||
auto as = rclcpp_action::create_server<Fibonacci>(
|
||||
node, "fibonacci",
|
||||
[](const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>) {
|
||||
return rclcpp_action::GoalResponse::REJECT;
|
||||
},
|
||||
[](std::shared_ptr<GoalHandle>) {
|
||||
return rclcpp_action::CancelResponse::REJECT;
|
||||
},
|
||||
[](std::shared_ptr<GoalHandle>) {});
|
||||
(void)as;
|
||||
}, rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestServer, handle_goal_called)
|
||||
{
|
||||
auto node = std::make_shared<rclcpp::Node>("handle_goal_node", "/rclcpp_action/handle_goal");
|
||||
|
@ -923,3 +982,238 @@ TEST_F(TestServer, deferred_execution)
|
|||
received_handle->execute();
|
||||
EXPECT_TRUE(received_handle->is_executing());
|
||||
}
|
||||
|
||||
class TestBasicServer : public TestServer
|
||||
{
|
||||
public:
|
||||
void SetUp()
|
||||
{
|
||||
node_ = std::make_shared<rclcpp::Node>("goal_request", "/rclcpp_action/goal_request");
|
||||
uuid_ = {{1, 2, 3, 4, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}};
|
||||
action_server_ = rclcpp_action::create_server<Fibonacci>(
|
||||
node_, "fibonacci",
|
||||
[](const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>) {
|
||||
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
|
||||
},
|
||||
[](std::shared_ptr<GoalHandle>) {
|
||||
return rclcpp_action::CancelResponse::ACCEPT;
|
||||
},
|
||||
[this](std::shared_ptr<GoalHandle> handle) {
|
||||
goal_handle_ = handle;
|
||||
});
|
||||
}
|
||||
|
||||
void SendClientGoalRequest(
|
||||
std::chrono::milliseconds timeout = std::chrono::milliseconds(-1))
|
||||
{
|
||||
send_goal_request(node_, uuid_, timeout);
|
||||
auto result_client = node_->create_client<Fibonacci::Impl::GetResultService>(
|
||||
"fibonacci/_action/get_result");
|
||||
if (!result_client->wait_for_service(std::chrono::seconds(20))) {
|
||||
throw std::runtime_error("get result service didn't become available");
|
||||
}
|
||||
auto request = std::make_shared<Fibonacci::Impl::GetResultService::Request>();
|
||||
request->goal_id.uuid = uuid_;
|
||||
auto future = result_client->async_send_request(request);
|
||||
|
||||
// Send a result
|
||||
auto result = std::make_shared<Fibonacci::Result>();
|
||||
result->sequence = {5, 8, 13, 21};
|
||||
goal_handle_->succeed(result);
|
||||
|
||||
// Wait for the result request to be received
|
||||
ASSERT_EQ(
|
||||
rclcpp::FutureReturnCode::SUCCESS,
|
||||
rclcpp::spin_until_future_complete(node_, future));
|
||||
|
||||
auto response = future.get();
|
||||
EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->status);
|
||||
EXPECT_EQ(result->sequence, response->result.sequence);
|
||||
|
||||
// Wait for goal expiration
|
||||
rclcpp::sleep_for(std::chrono::milliseconds(100));
|
||||
|
||||
// Allow for expiration to take place
|
||||
rclcpp::spin_some(node_);
|
||||
|
||||
// Send and wait for another result request
|
||||
future = result_client->async_send_request(request);
|
||||
ASSERT_EQ(
|
||||
rclcpp::FutureReturnCode::SUCCESS,
|
||||
rclcpp::spin_until_future_complete(node_, future));
|
||||
}
|
||||
|
||||
protected:
|
||||
GoalUUID uuid_;
|
||||
std::shared_ptr<rclcpp::Node> node_;
|
||||
std::shared_ptr<rclcpp_action::Server<Fibonacci>> action_server_;
|
||||
|
||||
using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>;
|
||||
std::shared_ptr<GoalHandle> goal_handle_;
|
||||
};
|
||||
|
||||
class TestGoalRequestServer : public TestBasicServer {};
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_take_goal)
|
||||
{
|
||||
EXPECT_NO_THROW(SendClientGoalRequest());
|
||||
}
|
||||
|
||||
class TestCancelRequestServer : public TestBasicServer
|
||||
{
|
||||
public:
|
||||
void SendClientCancelRequest(
|
||||
std::chrono::milliseconds timeout = std::chrono::milliseconds(-1))
|
||||
{
|
||||
send_goal_request(node_, uuid_, timeout);
|
||||
send_cancel_request(node_, uuid_, timeout);
|
||||
}
|
||||
};
|
||||
|
||||
TEST_F(TestCancelRequestServer, execute_goal_request_received_take_goal)
|
||||
{
|
||||
EXPECT_NO_THROW(SendClientCancelRequest());
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, is_ready_rcl_error) {
|
||||
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
auto rcl_context = node_->get_node_base_interface()->get_context()->get_rcl_context().get();
|
||||
ASSERT_EQ(
|
||||
RCL_RET_OK,
|
||||
rcl_wait_set_init(&wait_set, 10, 10, 10, 10, 10, 10, rcl_context, allocator));
|
||||
RCLCPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_wait_set_fini(&wait_set));
|
||||
});
|
||||
ASSERT_TRUE(action_server_->add_to_wait_set(&wait_set));
|
||||
|
||||
EXPECT_TRUE(action_server_->is_ready(&wait_set));
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_server_wait_set_get_entities_ready, RCL_RET_ERROR);
|
||||
EXPECT_THROW(action_server_->is_ready(&wait_set), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_take_goal_request_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_goal_request, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_send_goal_response_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_send_goal_response, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_accept_new_goal_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_accept_new_goal, nullptr);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), std::runtime_error);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_update_goal_state_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_update_goal_state, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, publish_status_server_get_goal_handles_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_server_get_goal_handles, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, publish_status_get_goal_status_array_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_get_goal_status_array, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, publish_status_publish_status_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_publish_status, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), std::runtime_error);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_take_failed)
|
||||
{
|
||||
auto mock = mocking_utils::inject_on_return(
|
||||
"lib:rclcpp_action", rcl_action_take_goal_request, RCL_RET_ACTION_SERVER_TAKE_FAILED);
|
||||
try {
|
||||
SendClientGoalRequest(std::chrono::milliseconds(100));
|
||||
ADD_FAILURE() << "SetupActionServerAndSpin did not throw, but was expected to";
|
||||
} catch (const std::runtime_error & e) {
|
||||
EXPECT_STREQ("send goal future timed out", e.what());
|
||||
} catch (...) {
|
||||
ADD_FAILURE() << "SetupActionServerAndSpin threw, but not the expected std::runtime_error";
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, get_result_rcl_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_result_request, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, send_result_rcl_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_send_result_response, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestCancelRequestServer, execute_cancel_request_received_take_cancel_request_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_cancel_request, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientCancelRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestCancelRequestServer, execute_cancel_request_received_take_failed)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_cancel_request, RCL_RET_ACTION_SERVER_TAKE_FAILED);
|
||||
try {
|
||||
SendClientCancelRequest(std::chrono::milliseconds(100));
|
||||
ADD_FAILURE() << "SetupActionServerAndSpin did not throw, but it was expected to";
|
||||
} catch (const std::runtime_error & e) {
|
||||
EXPECT_STREQ("cancel request future timed out", e.what());
|
||||
} catch (...) {
|
||||
ADD_FAILURE() << "SetupActionServerAndSpin threw, but not the expected std::runtime_error";
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestCancelRequestServer, publish_status_rcl_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_process_cancel_request, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientCancelRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestCancelRequestServer, publish_status_send_cancel_response_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_send_cancel_response, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientCancelRequest(), std::runtime_error);
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue