Skip to content

Commit

Permalink
Add Serv/Cli request/response QoS getters
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 Nov 1, 2021
1 parent 534305f commit b66f071
Show file tree
Hide file tree
Showing 6 changed files with 155 additions and 103 deletions.
23 changes: 20 additions & 3 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,7 +216,7 @@ class ClientBase
bool
exchange_in_use_by_wait_set_state(bool in_use_state);

/// Get the actual QoS settings, after the defaults have been determined.
/// Get the actual request publsher QoS settings, after the defaults have been determined.
/**
* The actual configuration applied when using RMW_QOS_POLICY_*_SYSTEM_DEFAULT
* can only be resolved after the creation of the client, and it
Expand All @@ -225,12 +225,29 @@ class ClientBase
* it will be set to RMW_QOS_POLICY_*_UNKNOWN.
* May throw runtime_error when an unexpected error occurs.
*
* \return The actual qos settings.
* \return The actual request publsher qos settings.
* \throws std::runtime_error if failed to get qos settings
*/
RCLCPP_PUBLIC
rclcpp::QoS
get_actual_qos() const;
get_request_publisher_actual_qos() const;

/// Get the actual response subscription QoS settings, after the defaults have been determined.
/**
* The actual configuration applied when using RMW_QOS_POLICY_*_SYSTEM_DEFAULT
* can only be resolved after the creation of the client, and it
* depends on the underlying rmw implementation.
* If the underlying setting in use can't be represented in ROS terms,
* it will be set to RMW_QOS_POLICY_*_UNKNOWN.
* May throw runtime_error when an unexpected error occurs.
*
* \return The actual response subscription qos settings.
* \throws std::runtime_error if failed to get qos settings
*/
RCLCPP_PUBLIC
rclcpp::QoS
get_response_subscription_actual_qos() const;


protected:
RCLCPP_DISABLE_COPY(ClientBase)
Expand Down
22 changes: 19 additions & 3 deletions rclcpp/include/rclcpp/service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ class ServiceBase
bool
exchange_in_use_by_wait_set_state(bool in_use_state);

/// Get the actual QoS settings, after the defaults have been determined.
/// Get the actual response publisher QoS settings, after the defaults have been determined.
/**
* The actual configuration applied when using RMW_QOS_POLICY_*_SYSTEM_DEFAULT
* can only be resolved after the creation of the service, and it
Expand All @@ -131,12 +131,28 @@ class ServiceBase
* it will be set to RMW_QOS_POLICY_*_UNKNOWN.
* May throw runtime_error when an unexpected error occurs.
*
* \return The actual qos settings.
* \return The actual response publisher qos settings.
* \throws std::runtime_error if failed to get qos settings
*/
RCLCPP_PUBLIC
rclcpp::QoS
get_actual_qos() const;
get_response_publisher_actual_qos() const;

/// Get the actual request subscription QoS settings, after the defaults have been determined.
/**
* The actual configuration applied when using RMW_QOS_POLICY_*_SYSTEM_DEFAULT
* can only be resolved after the creation of the service, and it
* depends on the underlying rmw implementation.
* If the underlying setting in use can't be represented in ROS terms,
* it will be set to RMW_QOS_POLICY_*_UNKNOWN.
* May throw runtime_error when an unexpected error occurs.
*
* \return The actual request subscription qos settings.
* \throws std::runtime_error if failed to get qos settings
*/
RCLCPP_PUBLIC
rclcpp::QoS
get_request_subscription_actual_qos() const;

protected:
RCLCPP_DISABLE_COPY(ServiceBase)
Expand Down
31 changes: 27 additions & 4 deletions rclcpp/src/rclcpp/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,14 +200,37 @@ ClientBase::exchange_in_use_by_wait_set_state(bool in_use_state)
}

rclcpp::QoS
ClientBase::get_actual_qos() const
ClientBase::get_request_publisher_actual_qos() const
{
const rmw_qos_profile_t * qos = rcl_client_get_actual_qos(client_handle_.get());
const rmw_qos_profile_t * qos =
rcl_client_request_publisher_get_actual_qos(client_handle_.get());
if (!qos) {
auto msg = std::string("failed to get client qos settings: ") + rcl_get_error_string().str;
auto msg = std::string("failed to get client's request publisher qos settings: ")
+ rcl_get_error_string().str;
rcl_reset_error();
throw std::runtime_error(msg);
}

return rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(*qos), *qos);
rclcpp::QoS request_publisher_qos =
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(*qos), *qos);

return request_publisher_qos;
}

rclcpp::QoS
ClientBase::get_response_subscription_actual_qos() const
{
const rmw_qos_profile_t * qos =
rcl_client_response_subscription_get_actual_qos(client_handle_.get());
if (!qos) {
auto msg = std::string("failed to get client's response subscription qos settings: ")
+ rcl_get_error_string().str;
rcl_reset_error();
throw std::runtime_error(msg);
}

rclcpp::QoS response_subscription_qos =
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(*qos), *qos);

return response_subscription_qos;
}
31 changes: 27 additions & 4 deletions rclcpp/src/rclcpp/service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,14 +86,37 @@ ServiceBase::exchange_in_use_by_wait_set_state(bool in_use_state)
}

rclcpp::QoS
ServiceBase::get_actual_qos() const
ServiceBase::get_response_publisher_actual_qos() const
{
const rmw_qos_profile_t * qos = rcl_service_get_actual_qos(service_handle_.get());
const rmw_qos_profile_t* qos =
rcl_service_response_publisher_get_actual_qos(service_handle_.get());
if (!qos) {
auto msg = std::string("failed to get service qos settings: ") + rcl_get_error_string().str;
auto msg = std::string("failed to get service's response publisher qos settings: ") +
rcl_get_error_string().str;
rcl_reset_error();
throw std::runtime_error(msg);
}

return rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(*qos), *qos);
rclcpp::QoS response_publisher_qos =
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(*qos), *qos);

return response_publisher_qos;
}

rclcpp::QoS
ServiceBase::get_request_subscription_actual_qos() const
{
const rmw_qos_profile_t* qos =
rcl_service_request_subscription_get_actual_qos(service_handle_.get());
if (!qos) {
auto msg = std::string("failed to get service's request subscription qos settings: ") +
rcl_get_error_string().str;
rcl_reset_error();
throw std::runtime_error(msg);
}

rclcpp::QoS request_subscription_qos =
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(*qos), *qos);

return request_subscription_qos;
}
74 changes: 30 additions & 44 deletions rclcpp/test/rclcpp/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -342,58 +342,44 @@ TEST_F(TestClientWithServer, take_response) {
}
}

TEST_F(TestClient, rcl_client_get_actual_qos_error) {
TEST_F(TestClient, rcl_client_request_publisher_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);
"lib:rclcpp", rcl_client_request_publisher_get_actual_qos, nullptr);
auto client = node->create_client<test_msgs::srv::Empty>("service");
RCLCPP_EXPECT_THROW_EQ(
client->get_actual_qos(),
std::runtime_error("failed to get client qos settings: error not set"));
client->get_request_publisher_actual_qos(),
std::runtime_error("failed to get client's request publisher 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, rcl_client_response_subscription_get_actual_qos_error) {
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_client_response_subscription_get_actual_qos, nullptr);
auto client = node->create_client<test_msgs::srv::Empty>("service");
RCLCPP_EXPECT_THROW_EQ(
client->get_response_subscription_actual_qos(),
std::runtime_error("failed to get client's response subscription qos settings: error not set"));
}

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;
rmw_qos_profile_t qos_profile = rmw_qos_profile_services_default;
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());
uint64_t duration = 1;
qos_profile.deadline = {duration, duration};
qos_profile.lifespan = {duration, duration};
qos_profile.liveliness_lease_duration = {duration, duration};

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

auto init_qos =
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile), qos_profile);
auto rp_qos = client->get_request_publisher_actual_qos();
auto rs_qos = client->get_response_subscription_actual_qos();

EXPECT_EQ(init_qos, rp_qos);
// Lifespan has no meaning for subscription/readers
rs_qos.lifespan(qos_profile.lifespan);
EXPECT_EQ(init_qos, rs_qos);
}

TEST_F(TestClient, client_qos_depth) {
Expand Down
77 changes: 32 additions & 45 deletions rclcpp/test/rclcpp/test_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,66 +237,53 @@ TEST_F(TestService, send_response) {
}
}

TEST_F(TestService, rcl_service_get_actual_qos_error) {
TEST_F(TestService, rcl_service_response_publisher_get_actual_qos_error) {
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_service_get_actual_qos, nullptr);
"lib:rclcpp", rcl_service_response_publisher_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"));
server->get_response_publisher_actual_qos(),
std::runtime_error("failed to get service's response publisher 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_F(TestService, rcl_service_request_subscription_get_actual_qos_error) {
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_service_request_subscription_get_actual_qos, nullptr);
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);
auto server = node->create_service<test_msgs::srv::Empty>("service", callback);
RCLCPP_EXPECT_THROW_EQ(
server->get_request_subscription_actual_qos(),
std::runtime_error("failed to get service's request subscription qos settings: error not set"));
}


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;
rmw_qos_profile_t qos_profile = rmw_qos_profile_services_default;
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;
uint64_t duration = 1;
qos_profile.deadline = {duration, duration};
qos_profile.lifespan = {duration, duration};
qos_profile.liveliness_lease_duration = {duration, duration};

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_msgs::srv::Empty::Response::SharedPtr) {};

auto server = node->create_service<test_msgs::srv::Empty>("service", callback,
qos_profile);
auto init_qos =
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile), qos_profile);
auto rs_qos = server->get_request_subscription_actual_qos();
auto rp_qos = server->get_response_publisher_actual_qos();

EXPECT_EQ(init_qos, rp_qos);
// Lifespan has no meaning for subscription/readers
rs_qos.lifespan(qos_profile.lifespan);
EXPECT_EQ(init_qos, rs_qos);
}

TEST_F(TestService, server_qos_depth) {
Expand Down

0 comments on commit b66f071

Please sign in to comment.