Increase service coverage (#1332)
Signed-off-by: Stephen Brawner <brawner@gmail.com>
This commit is contained in:
parent
e700d3becd
commit
443fc180c7
2 changed files with 88 additions and 1 deletions
|
@ -394,7 +394,7 @@ if(TARGET test_service)
|
|||
"rosidl_typesupport_cpp"
|
||||
"test_msgs"
|
||||
)
|
||||
target_link_libraries(test_service ${PROJECT_NAME})
|
||||
target_link_libraries(test_service ${PROJECT_NAME} mimick)
|
||||
endif()
|
||||
ament_add_gtest(test_subscription rclcpp/test_subscription.cpp)
|
||||
if(TARGET test_subscription)
|
||||
|
|
|
@ -16,10 +16,13 @@
|
|||
|
||||
#include <string>
|
||||
#include <memory>
|
||||
#include <utility>
|
||||
|
||||
#include "rclcpp/exceptions.hpp"
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
#include "../mocking_utils/patch.hpp"
|
||||
|
||||
#include "rcl_interfaces/srv/list_parameters.hpp"
|
||||
#include "test_msgs/srv/empty.hpp"
|
||||
#include "test_msgs/srv/empty.h"
|
||||
|
@ -32,6 +35,11 @@ protected:
|
|||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
static void TearDownTestCase()
|
||||
{
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
|
||||
void SetUp()
|
||||
{
|
||||
node = std::make_shared<rclcpp::Node>("my_node", "/ns");
|
||||
|
@ -50,6 +58,12 @@ class TestServiceSub : public ::testing::Test
|
|||
protected:
|
||||
static void SetUpTestCase()
|
||||
{
|
||||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
static void TearDownTestCase()
|
||||
{
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
|
||||
void SetUp()
|
||||
|
@ -77,6 +91,9 @@ TEST_F(TestService, construction_and_destruction) {
|
|||
};
|
||||
{
|
||||
auto service = node->create_service<ListParameters>("service", callback);
|
||||
EXPECT_NE(nullptr, service->get_service_handle());
|
||||
const rclcpp::ServiceBase * const_service_base = service.get();
|
||||
EXPECT_NE(nullptr, const_service_base->get_service_handle());
|
||||
}
|
||||
|
||||
{
|
||||
|
@ -108,6 +125,25 @@ TEST_F(TestServiceSub, construction_and_destruction) {
|
|||
}
|
||||
}
|
||||
|
||||
TEST_F(TestService, construction_and_destruction_rcl_errors) {
|
||||
auto callback =
|
||||
[](const test_msgs::srv::Empty::Request::SharedPtr,
|
||||
test_msgs::srv::Empty::Response::SharedPtr) {};
|
||||
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_service_init, RCL_RET_ERROR);
|
||||
// reset() isn't necessary for this exception, it just avoids unused return value warning
|
||||
EXPECT_THROW(
|
||||
node->create_service<test_msgs::srv::Empty>("service", callback).reset(),
|
||||
rclcpp::exceptions::RCLError);
|
||||
}
|
||||
{
|
||||
// reset() is required for this one
|
||||
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_service_fini, RCL_RET_ERROR);
|
||||
EXPECT_NO_THROW(node->create_service<test_msgs::srv::Empty>("service", callback).reset());
|
||||
}
|
||||
}
|
||||
|
||||
/* Testing basic getters */
|
||||
TEST_F(TestService, basic_public_getters) {
|
||||
using rcl_interfaces::srv::ListParameters;
|
||||
|
@ -148,3 +184,54 @@ TEST_F(TestService, basic_public_getters) {
|
|||
node_handle_int->get_node_base_interface()->get_rcl_node_handle()));
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestService, take_request) {
|
||||
auto callback =
|
||||
[](const test_msgs::srv::Empty::Request::SharedPtr,
|
||||
test_msgs::srv::Empty::Response::SharedPtr) {};
|
||||
auto server = node->create_service<test_msgs::srv::Empty>("service", callback);
|
||||
{
|
||||
auto request_id = server->create_request_header();
|
||||
test_msgs::srv::Empty::Request request;
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp", rcl_take_request, RCL_RET_OK);
|
||||
EXPECT_TRUE(server->take_request(request, *request_id.get()));
|
||||
}
|
||||
{
|
||||
auto request_id = server->create_request_header();
|
||||
test_msgs::srv::Empty::Request request;
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp", rcl_take_request, RCL_RET_SERVICE_TAKE_FAILED);
|
||||
EXPECT_FALSE(server->take_request(request, *request_id.get()));
|
||||
}
|
||||
{
|
||||
auto request_id = server->create_request_header();
|
||||
test_msgs::srv::Empty::Request request;
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp", rcl_take_request, RCL_RET_ERROR);
|
||||
EXPECT_THROW(server->take_request(request, *request_id.get()), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestService, send_response) {
|
||||
auto callback =
|
||||
[](const test_msgs::srv::Empty::Request::SharedPtr,
|
||||
test_msgs::srv::Empty::Response::SharedPtr) {};
|
||||
auto server = node->create_service<test_msgs::srv::Empty>("service", callback);
|
||||
|
||||
{
|
||||
auto request_id = server->create_request_header();
|
||||
test_msgs::srv::Empty::Response response;
|
||||
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_send_response, RCL_RET_OK);
|
||||
EXPECT_NO_THROW(server->send_response(*request_id.get(), response));
|
||||
}
|
||||
|
||||
{
|
||||
auto request_id = server->create_request_header();
|
||||
test_msgs::srv::Empty::Response response;
|
||||
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_send_response, RCL_RET_ERROR);
|
||||
EXPECT_THROW(
|
||||
server->send_response(*request_id.get(), response),
|
||||
rclcpp::exceptions::RCLError);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue