Skip to content

Commit

Permalink
Add client/service QoS unit tests
Browse files Browse the repository at this point in the history
Signed-off-by: Mauro Passerino <mpasserino@irobot.com>
  • Loading branch information
Mauro Passerino committed Oct 15, 2021
1 parent fadadc8 commit 534305f
Show file tree
Hide file tree
Showing 2 changed files with 230 additions and 0 deletions.
117 changes: 117 additions & 0 deletions rclcpp/test/rclcpp/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include "rcl_interfaces/srv/list_parameters.hpp"

#include "../mocking_utils/patch.hpp"
#include "../utils/rclcpp_gtest_macros.hpp"

#include "test_msgs/srv/empty.hpp"

Expand Down Expand Up @@ -340,3 +341,119 @@ TEST_F(TestClientWithServer, take_response) {
rclcpp::exceptions::RCLError);
}
}

TEST_F(TestClient, rcl_client_get_actual_qos_error) {
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_client_get_actual_qos, nullptr);
const std::string service_name = "service";
auto client = node->create_client<test_msgs::srv::Empty>(service_name);
RCLCPP_EXPECT_THROW_EQ(
client->get_actual_qos(),
std::runtime_error("failed to get client qos settings: error not set"));
}

TEST_F(TestClient, client_qos_error) {
rmw_qos_profile_t qos_profile = rmw_qos_profile_system_default;
EXPECT_THROW(
node->create_client<test_msgs::srv::Empty>("client", qos_profile),
rclcpp::exceptions::RCLError);
}

TEST_F(TestClient, client_qos) {
rmw_qos_profile_t qos_profile;
qos_profile.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
qos_profile.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
qos_profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
qos_profile.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
qos_profile.depth = 1;
uint64_t duration = 2;
qos_profile.deadline.sec = duration;
qos_profile.lifespan.sec = duration;
qos_profile.liveliness_lease_duration.sec = duration;
qos_profile.deadline.nsec = 0;
qos_profile.lifespan.nsec = 0;
qos_profile.liveliness_lease_duration.nsec = 0;
qos_profile.avoid_ros_namespace_conventions = false;

auto client = node->create_client<test_msgs::srv::Empty>("client", qos_profile);

EXPECT_EQ(rclcpp::ReliabilityPolicy::BestEffort, client->get_actual_qos().reliability());
EXPECT_EQ(rclcpp::DurabilityPolicy::Volatile, client->get_actual_qos().durability());
EXPECT_EQ(rclcpp::LivelinessPolicy::Automatic, client->get_actual_qos().liveliness());
EXPECT_EQ(rclcpp::HistoryPolicy::KeepLast, client->get_actual_qos().history());
EXPECT_EQ(qos_profile.depth, client->get_actual_qos().depth());
EXPECT_EQ(
duration,
static_cast<uint64_t>(client->get_actual_qos().deadline().seconds()));
EXPECT_EQ(
duration,
static_cast<uint64_t>(client->get_actual_qos().lifespan().seconds()));
EXPECT_EQ(
duration,
static_cast<uint64_t>(client->get_actual_qos().liveliness_lease_duration().seconds()));
EXPECT_EQ(
qos_profile.avoid_ros_namespace_conventions,
client->get_actual_qos().avoid_ros_namespace_conventions());
}

TEST_F(TestClient, client_qos_depth) {
using namespace std::literals::chrono_literals;

rmw_qos_profile_t client_qos_profile = rmw_qos_profile_default;
client_qos_profile.depth = 2;

auto client = node->create_client<test_msgs::srv::Empty>("test_qos_depth", client_qos_profile);

uint64_t server_cb_count_ = 0;
auto server_callback = [&](
const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {server_cb_count_++;};

auto server_node = std::make_shared<rclcpp::Node>("server_node", "/ns");

rmw_qos_profile_t server_qos_profile = rmw_qos_profile_default;

auto server = server_node->create_service<test_msgs::srv::Empty>(
"test_qos_depth", std::move(server_callback), server_qos_profile);

auto request = std::make_shared<test_msgs::srv::Empty::Request>();
::testing::AssertionResult request_result = ::testing::AssertionSuccess();

using SharedFuture = rclcpp::Client<test_msgs::srv::Empty>::SharedFuture;
uint64_t client_cb_count_ = 0;
auto client_callback = [&client_cb_count_, &request_result](SharedFuture future_response) {
if (nullptr == future_response.get()) {
request_result = ::testing::AssertionFailure() << "Future response was null";
}
client_cb_count_++;
};

uint64_t client_requests = 5;
for (uint64_t i = 0; i < client_requests; i++) {
client->async_send_request(request, client_callback);
std::this_thread::sleep_for(10ms);
}

auto start = std::chrono::steady_clock::now();
while ((server_cb_count_ < client_requests) &&
(std::chrono::steady_clock::now() - start) < 2s)
{
rclcpp::spin_some(server_node);
std::this_thread::sleep_for(2ms);
}

EXPECT_GT(server_cb_count_, client_qos_profile.depth);

start = std::chrono::steady_clock::now();
while ((client_cb_count_ < client_qos_profile.depth) &&
(std::chrono::steady_clock::now() - start) < 1s)
{
rclcpp::spin_some(node);
}

// Spin an extra time to check if client QoS depth has been ignored,
// so more client callbacks might be called than expected.
rclcpp::spin_some(node);

EXPECT_EQ(client_cb_count_, client_qos_profile.depth);
}
113 changes: 113 additions & 0 deletions rclcpp/test/rclcpp/test_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include "rclcpp/rclcpp.hpp"

#include "../mocking_utils/patch.hpp"
#include "../utils/rclcpp_gtest_macros.hpp"

#include "rcl_interfaces/srv/list_parameters.hpp"
#include "test_msgs/srv/empty.hpp"
Expand Down Expand Up @@ -235,3 +236,115 @@ TEST_F(TestService, send_response) {
rclcpp::exceptions::RCLError);
}
}

TEST_F(TestService, rcl_service_get_actual_qos_error) {
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_service_get_actual_qos, nullptr);
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);
RCLCPP_EXPECT_THROW_EQ(
server->get_actual_qos(),
std::runtime_error("failed to get service qos settings: error not set"));
}

TEST_F(TestService, server_qos_error) {
rmw_qos_profile_t qos_profile = rmw_qos_profile_system_default;
auto callback = [](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};

EXPECT_THROW(
node->create_service<test_msgs::srv::Empty>("service", callback, qos_profile),
rclcpp::exceptions::RCLError);
}

TEST_F(TestService, server_qos) {
rmw_qos_profile_t qos_profile;
qos_profile.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
qos_profile.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
qos_profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
qos_profile.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
qos_profile.depth = 1;
uint64_t duration = 2;
qos_profile.deadline.sec = duration;
qos_profile.lifespan.sec = duration;
qos_profile.liveliness_lease_duration.sec = duration;
qos_profile.deadline.nsec = 0;
qos_profile.lifespan.nsec = 0;
qos_profile.liveliness_lease_duration.nsec = 0;
qos_profile.avoid_ros_namespace_conventions = false;

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, qos_profile);

EXPECT_EQ(rclcpp::ReliabilityPolicy::BestEffort, server->get_actual_qos().reliability());
EXPECT_EQ(rclcpp::DurabilityPolicy::Volatile, server->get_actual_qos().durability());
EXPECT_EQ(rclcpp::LivelinessPolicy::Automatic, server->get_actual_qos().liveliness());
EXPECT_EQ(rclcpp::HistoryPolicy::KeepLast, server->get_actual_qos().history());
EXPECT_EQ(qos_profile.depth, server->get_actual_qos().depth());
EXPECT_EQ(
duration,
static_cast<uint64_t>(server->get_actual_qos().deadline().seconds()));
EXPECT_EQ(
duration,
static_cast<uint64_t>(server->get_actual_qos().lifespan().seconds()));
EXPECT_EQ(
duration,
static_cast<uint64_t>(server->get_actual_qos().liveliness_lease_duration().seconds()));
EXPECT_EQ(
qos_profile.avoid_ros_namespace_conventions,
server->get_actual_qos().avoid_ros_namespace_conventions());
}

TEST_F(TestService, server_qos_depth) {
using namespace std::literals::chrono_literals;

uint64_t server_cb_count_ = 0;
auto server_callback = [&](
const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {server_cb_count_++;};

auto server_node = std::make_shared<rclcpp::Node>("server_node", "/ns");

rmw_qos_profile_t server_qos_profile = rmw_qos_profile_default;
server_qos_profile.depth = 2;

auto server = server_node->create_service<test_msgs::srv::Empty>(
"test_qos_depth", std::move(server_callback), server_qos_profile);

rmw_qos_profile_t client_qos_profile = rmw_qos_profile_default;
auto client = node->create_client<test_msgs::srv::Empty>("test_qos_depth", client_qos_profile);

::testing::AssertionResult request_result = ::testing::AssertionSuccess();
auto request = std::make_shared<test_msgs::srv::Empty::Request>();

using SharedFuture = rclcpp::Client<test_msgs::srv::Empty>::SharedFuture;
auto client_callback = [&request_result](SharedFuture future_response) {
if (nullptr == future_response.get()) {
request_result = ::testing::AssertionFailure() << "Future response was null";
}
};

uint64_t client_requests = 5;
for (uint64_t i = 0; i < client_requests; i++) {
client->async_send_request(request, client_callback);
std::this_thread::sleep_for(10ms);
}

auto start = std::chrono::steady_clock::now();
while ((server_cb_count_ < server_qos_profile.depth) &&
(std::chrono::steady_clock::now() - start) < 1s)
{
rclcpp::spin_some(server_node);
std::this_thread::sleep_for(1ms);
}

// Spin an extra time to check if server QoS depth has been ignored,
// so more server responses might be processed than expected.
rclcpp::spin_some(server_node);

EXPECT_EQ(server_cb_count_, server_qos_profile.depth);
}

0 comments on commit 534305f

Please sign in to comment.