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

Increase service coverage #1332

Merged
merged 1 commit into from
Sep 28, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
2 changes: 1 addition & 1 deletion rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -401,7 +401,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)
Expand Down
87 changes: 87 additions & 0 deletions rclcpp/test/rclcpp/test_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand All @@ -32,6 +35,11 @@ class TestService : public ::testing::Test
rclcpp::init(0, nullptr);
}

static void TearDownTestCase()
{
rclcpp::shutdown();
}

void SetUp()
{
node = std::make_shared<rclcpp::Node>("my_node", "/ns");
Expand All @@ -50,6 +58,12 @@ class TestServiceSub : public ::testing::Test
protected:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}

static void TearDownTestCase()
{
rclcpp::shutdown();
}

void SetUp()
Expand Down Expand Up @@ -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());
}

{
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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);
}
}