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

Implement get_actual_qos() for subscriptions #455

Merged
merged 5 commits into from
Jun 12, 2019
Merged
Show file tree
Hide file tree
Changes from 2 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
26 changes: 26 additions & 0 deletions rcl/include/rcl/subscription.h
Original file line number Diff line number Diff line change
Expand Up @@ -445,6 +445,32 @@ rcl_subscription_get_publisher_count(
const rcl_subscription_t * subscription,
size_t * publisher_count);

/// Get the actual qos settings of the subscription.
/**
* Used to get the actual qos settings of the subscription.
* The actual configuration applied when using RMW_*_SYSTEM_DEFAULT
* can only be resolved after the creation of the subscription, 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_*_UNKNOWN.
* The returned struct is only valid as long as the rcl_subscription_t is valid.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | Yes
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[in] subscription pointer to the rcl subscription
* \return qos struct if successful, otherwise `NULL`
*/
RCL_PUBLIC
RCL_WARN_UNUSED
const rmw_qos_profile_t *
rcl_subscription_get_actual_qos(const rcl_subscription_t * subscription);

#ifdef __cplusplus
}
#endif
Expand Down
20 changes: 20 additions & 0 deletions rcl/src/rcl/subscription.c
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,17 @@ rcl_subscription_init(
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
goto fail;
}
// get actual qos, and store it
rmw_ret = rmw_subscription_get_actual_qos(
subscription->impl->rmw_handle,
&subscription->impl->actual_qos);
if (RMW_RET_OK != rmw_ret) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
ret = RCL_RET_ERROR;
goto fail;
}
subscription->impl->actual_qos.avoid_ros_namespace_conventions =
options->qos.avoid_ros_namespace_conventions;
// options
subscription->impl->options = *options;
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription initialized");
Expand Down Expand Up @@ -359,6 +370,15 @@ rcl_subscription_get_publisher_count(
return RCL_RET_OK;
}

const rmw_qos_profile_t *
rcl_subscription_get_actual_qos(const rcl_subscription_t * subscription)
{
if (!rcl_subscription_is_valid(subscription)) {
return NULL;
}
return &subscription->impl->actual_qos;
}

#ifdef __cplusplus
}
#endif
1 change: 1 addition & 0 deletions rcl/src/rcl/subscription_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
typedef struct rcl_subscription_impl_t
{
rcl_subscription_options_t options;
rmw_qos_profile_t actual_qos;
rmw_subscription_t * rmw_handle;
} rcl_subscription_impl_t;

Expand Down
134 changes: 114 additions & 20 deletions rcl/test/rcl/test_get_actual_qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ std::ostream & operator<<(
return out;
}

class TEST_FIXTURE_P_RMW (TestGetActualQoS)
class TEST_FIXTURE_P_RMW(TestGetActualQoS)
: public ::testing::TestWithParam<TestParameters>
{
public:
Expand Down Expand Up @@ -114,7 +114,11 @@ class TEST_FIXTURE_P_RMW (TestGetActualQoS)
rcl_context_t * context_ptr;
};

TEST_P_RMW(TestGetActualQoS, test_publisher_get_qos_settings) {

class TEST_FIXTURE_P_RMW(TestPublisherGetActualQoS)
: public TEST_FIXTURE_P_RMW(TestGetActualQoS) {};

TEST_P_RMW(TestPublisherGetActualQoS, test_publisher_get_qos_settings) {
TestParameters parameters = GetParam();
std::string topic_name("/test_publisher_get_actual_qos__");
rcl_ret_t ret;
Expand Down Expand Up @@ -142,6 +146,9 @@ TEST_P_RMW(TestGetActualQoS, test_publisher_get_qos_settings) {
EXPECT_EQ(
qos->durability,
parameters.qos_expected.durability);
EXPECT_EQ(
qos->liveliness,
parameters.qos_expected.liveliness);
EXPECT_EQ(
qos->avoid_ros_namespace_conventions,
parameters.qos_expected.avoid_ros_namespace_conventions);
Expand All @@ -151,7 +158,61 @@ TEST_P_RMW(TestGetActualQoS, test_publisher_get_qos_settings) {
rcl_reset_error();
}

static constexpr rmw_qos_profile_t non_default_qos_profile()

class TEST_FIXTURE_P_RMW(TestSubscriptionGetActualQoS)
: public TEST_FIXTURE_P_RMW(TestGetActualQoS) {};

TEST_P_RMW(TestSubscriptionGetActualQoS, test_subscription_get_qos_settings) {
TestParameters parameters = GetParam();
std::string topic_name("/test_subscription_get_qos_settings");
rcl_ret_t ret;

rcl_subscription_t pub = rcl_get_zero_initialized_subscription();
rcl_subscription_options_t pub_ops = rcl_subscription_get_default_options();
pub_ops.qos = parameters.qos_to_set;
auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes);
ret = rcl_subscription_init(&pub, this->node_ptr, ts, topic_name.c_str(), &pub_ops);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error();

const rmw_qos_profile_t * qos;
qos = rcl_subscription_get_actual_qos(&pub);
EXPECT_NE(nullptr, qos) << rcl_get_error_string().str;
EXPECT_EQ(
qos->history,
parameters.qos_expected.history);
EXPECT_EQ(
qos->depth,
parameters.qos_expected.depth);
EXPECT_EQ(
qos->reliability,
parameters.qos_expected.reliability);
EXPECT_EQ(
qos->durability,
parameters.qos_expected.durability);
EXPECT_EQ(
qos->liveliness,
parameters.qos_expected.liveliness);
EXPECT_EQ(
qos->avoid_ros_namespace_conventions,
parameters.qos_expected.avoid_ros_namespace_conventions);

ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
ret = rcl_subscription_fini(&pub, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error();
}


static constexpr rmw_qos_profile_t
expected_default_qos_profile()
{
rmw_qos_profile_t profile = rmw_qos_profile_default;
profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
return profile;
}

static constexpr rmw_qos_profile_t
expected_nondefault_qos_profile()
{
rmw_qos_profile_t profile = rmw_qos_profile_default;
profile.history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
Expand All @@ -163,7 +224,17 @@ static constexpr rmw_qos_profile_t non_default_qos_profile()
return profile;
}

static constexpr rmw_qos_profile_t expected_fastrtps_default_qos_profile()
static constexpr rmw_qos_profile_t
expected_system_default_publisher_qos_profile()
{
rmw_qos_profile_t profile = rmw_qos_profile_default;
profile.depth = 1;
profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
return profile;
}

static constexpr rmw_qos_profile_t
expected_system_default_publisher_qos_profile_for_fastrtps()
{
rmw_qos_profile_t profile = rmw_qos_profile_default;
profile.depth = 1;
Expand All @@ -172,16 +243,29 @@ static constexpr rmw_qos_profile_t expected_fastrtps_default_qos_profile()
return profile;
}

static constexpr rmw_qos_profile_t expected_system_default_qos_profile()
static constexpr rmw_qos_profile_t
expected_system_default_subscription_qos_profile()
{
rmw_qos_profile_t profile = rmw_qos_profile_default;
profile.depth = 1;
profile.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
return profile;
}

static constexpr rmw_qos_profile_t
expected_system_default_subscription_qos_profile_for_fastrtps()
{
rmw_qos_profile_t profile = rmw_qos_profile_default;
profile.depth = 1;
profile.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
profile.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
return profile;
}

std::vector<TestParameters>
get_parameters()
get_parameters(bool for_publisher)
{
std::vector<TestParameters>
parameters({
Expand All @@ -190,16 +274,16 @@ get_parameters()
*/
{
rmw_qos_profile_default,
rmw_qos_profile_default,
"publisher_default_qos"
expected_default_qos_profile(),
"default_qos"
},
/*
Test with non-default settings.
*/
{
non_default_qos_profile(),
non_default_qos_profile(),
"publisher_non_default_qos"
expected_nondefault_qos_profile(),
expected_nondefault_qos_profile(),
"nondefault_qos"
}
});

Expand All @@ -208,21 +292,25 @@ get_parameters()
if (rmw_implementation_str == "rmw_fastrtps_cpp" ||
rmw_implementation_str == "rmw_fastrtps_dynamic_cpp")
{
rmw_qos_profile_t expected_system_default_qos = expected_fastrtps_default_qos_profile();
rmw_qos_profile_t expected_qos = for_publisher ?
expected_system_default_publisher_qos_profile_for_fastrtps() :
expected_system_default_subscription_qos_profile_for_fastrtps();
parameters.push_back({
rmw_qos_profile_system_default,
expected_system_default_qos,
"publisher_system_default_qos"});
expected_qos,
"system_default_publisher_qos"});
} else {
if (rmw_implementation_str == "rmw_connext_cpp" ||
rmw_implementation_str == "rmw_connext_dynamic_cpp" ||
rmw_implementation_str == "rmw_opensplice_cpp")
{
rmw_qos_profile_t expected_system_default_qos = expected_system_default_qos_profile();
rmw_qos_profile_t expected_qos = for_publisher ?
expected_system_default_publisher_qos_profile() :
expected_system_default_subscription_qos_profile();
parameters.push_back({
rmw_qos_profile_system_default,
expected_system_default_qos,
"publisher_system_default_qos"});
expected_qos,
"system_default_publisher_qos"});
}
}
#endif
Expand All @@ -231,7 +319,13 @@ get_parameters()
}

INSTANTIATE_TEST_CASE_P_RMW(
TestWithDifferentQoSSettings,
TestGetActualQoS,
::testing::ValuesIn(get_parameters()),
TestPublisherWithDifferentQoSSettings,
TestPublisherGetActualQoS,
::testing::ValuesIn(get_parameters(true)),
::testing::PrintToStringParamName());

INSTANTIATE_TEST_CASE_P_RMW(
TestSubscriptionWithDifferentQoSSettings,
TestSubscriptionGetActualQoS,
::testing::ValuesIn(get_parameters(false)),
::testing::PrintToStringParamName());