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

Take and return new RMW_DURATION_INFINITE correctly #515

Merged
merged 1 commit into from
Mar 17, 2021
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
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,10 @@ get_datawriter_qos(
const rmw_qos_profile_t & qos_policies,
eprosima::fastrtps::PublisherAttributes & pattr);

RMW_FASTRTPS_SHARED_CPP_PUBLIC
rmw_time_t
dds_duration_to_rmw(const eprosima::fastrtps::Duration_t & duration);

/*
* Converts the low-level QOS Policy; of type WriterQos or ReaderQos into rmw_qos_profile_t.
* Since WriterQos or ReaderQos does not have information about history and depth, these values are not set
Expand Down Expand Up @@ -89,11 +93,8 @@ dds_qos_to_rmw_qos(
break;
}

qos->deadline.sec = dds_qos.m_deadline.period.seconds;
qos->deadline.nsec = dds_qos.m_deadline.period.nanosec;

qos->lifespan.sec = dds_qos.m_lifespan.duration.seconds;
qos->lifespan.nsec = dds_qos.m_lifespan.duration.nanosec;
qos->deadline = dds_duration_to_rmw(dds_qos.m_deadline.period);
qos->lifespan = dds_duration_to_rmw(dds_qos.m_lifespan.duration);

switch (dds_qos.m_liveliness.kind) {
case eprosima::fastrtps::AUTOMATIC_LIVELINESS_QOS:
Expand All @@ -106,8 +107,7 @@ dds_qos_to_rmw_qos(
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_UNKNOWN;
break;
}
qos->liveliness_lease_duration.sec = dds_qos.m_liveliness.lease_duration.seconds;
qos->liveliness_lease_duration.nsec = dds_qos.m_liveliness.lease_duration.nanosec;
qos->liveliness_lease_duration = dds_duration_to_rmw(dds_qos.m_liveliness.lease_duration);
}

template<typename AttributeT>
Expand Down
24 changes: 19 additions & 5 deletions rmw_fastrtps_shared_cpp/src/qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,10 @@ static
eprosima::fastrtps::Duration_t
rmw_time_to_fastrtps(const rmw_time_t & time)
{
if (rmw_time_equal(time, RMW_DURATION_INFINITE)) {
return eprosima::fastrtps::rtps::c_RTPSTimeInfinite.to_duration_t();
}

rmw_time_t clamped_time = rmw_dds_common::clamp_rmw_time_to_dds_time(time);
return eprosima::fastrtps::Duration_t(
static_cast<int32_t>(clamped_time.sec),
Expand All @@ -34,9 +38,19 @@ rmw_time_to_fastrtps(const rmw_time_t & time)

static
bool
is_time_default(const rmw_time_t & time)
is_rmw_duration_unspecified(const rmw_time_t & time)
{
return rmw_time_equal(time, RMW_DURATION_UNSPECIFIED);
}

rmw_time_t
dds_duration_to_rmw(const eprosima::fastrtps::Duration_t & duration)
{
return time.sec == 0 && time.nsec == 0;
if (duration == eprosima::fastrtps::rtps::c_RTPSTimeInfinite) {
return RMW_DURATION_INFINITE;
}
rmw_time_t result = {(uint64_t)duration.seconds, (uint64_t)duration.nanosec};
return result;
}

template<typename DDSEntityQos>
Expand Down Expand Up @@ -101,11 +115,11 @@ bool fill_entity_qos_from_profile(
history_qos.depth = static_cast<int32_t>(qos_policies.depth);
}

if (!is_time_default(qos_policies.lifespan)) {
if (!is_rmw_duration_unspecified(qos_policies.lifespan)) {
entity_qos.m_lifespan.duration = rmw_time_to_fastrtps(qos_policies.lifespan);
}

if (!is_time_default(qos_policies.deadline)) {
if (!is_rmw_duration_unspecified(qos_policies.deadline)) {
entity_qos.m_deadline.period = rmw_time_to_fastrtps(qos_policies.deadline);
}

Expand All @@ -122,7 +136,7 @@ bool fill_entity_qos_from_profile(
RMW_SET_ERROR_MSG("Unknown QoS Liveliness policy");
return false;
}
if (!is_time_default(qos_policies.liveliness_lease_duration)) {
if (!is_rmw_duration_unspecified(qos_policies.liveliness_lease_duration)) {
entity_qos.m_liveliness.lease_duration =
rmw_time_to_fastrtps(qos_policies.liveliness_lease_duration);

Expand Down
22 changes: 22 additions & 0 deletions rmw_fastrtps_shared_cpp/test/test_dds_attributes_to_rmw_qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@

using eprosima::fastrtps::PublisherAttributes;
using eprosima::fastrtps::SubscriberAttributes;
static const eprosima::fastrtps::Duration_t InfiniteDuration =
eprosima::fastrtps::rtps::c_RTPSTimeInfinite.to_duration_t();

class DDSAttributesToRMWQosTest : public ::testing::Test
{
Expand Down Expand Up @@ -136,3 +138,23 @@ TEST_F(DDSAttributesToRMWQosTest, test_subscriber_lifespan_conversion) {
EXPECT_EQ(qos_profile_.lifespan.sec, 9u);
EXPECT_EQ(qos_profile_.lifespan.nsec, 432u);
}

TEST_F(DDSAttributesToRMWQosTest, test_subscriber_infinite_duration_conversions) {
subscriber_attributes_.qos.m_lifespan.duration = InfiniteDuration;
subscriber_attributes_.qos.m_deadline.period = InfiniteDuration;
subscriber_attributes_.qos.m_liveliness.lease_duration = InfiniteDuration;
dds_attributes_to_rmw_qos(subscriber_attributes_, &qos_profile_);
EXPECT_TRUE(rmw_time_equal(qos_profile_.deadline, RMW_DURATION_INFINITE));
EXPECT_TRUE(rmw_time_equal(qos_profile_.lifespan, RMW_DURATION_INFINITE));
EXPECT_TRUE(rmw_time_equal(qos_profile_.liveliness_lease_duration, RMW_DURATION_INFINITE));
}

TEST_F(DDSAttributesToRMWQosTest, test_publisher_infinite_duration_conversions) {
publisher_attributes_.qos.m_lifespan.duration = InfiniteDuration;
publisher_attributes_.qos.m_deadline.period = InfiniteDuration;
publisher_attributes_.qos.m_liveliness.lease_duration = InfiniteDuration;
dds_attributes_to_rmw_qos(publisher_attributes_, &qos_profile_);
EXPECT_TRUE(rmw_time_equal(qos_profile_.deadline, RMW_DURATION_INFINITE));
EXPECT_TRUE(rmw_time_equal(qos_profile_.lifespan, RMW_DURATION_INFINITE));
EXPECT_TRUE(rmw_time_equal(qos_profile_.liveliness_lease_duration, RMW_DURATION_INFINITE));
}
24 changes: 24 additions & 0 deletions rmw_fastrtps_shared_cpp/test/test_rmw_qos_to_dds_attributes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@


using eprosima::fastrtps::SubscriberAttributes;
static const eprosima::fastrtps::Duration_t InfiniteDuration =
eprosima::fastrtps::rtps::c_RTPSTimeInfinite.to_duration_t();

class GetDataReaderQoSTest : public ::testing::Test
{
Expand Down Expand Up @@ -220,3 +222,25 @@ TEST_F(GetDataWriterQoSTest, large_depth_conversion) {
EXPECT_FALSE(get_datawriter_qos(qos_profile_, publisher_attributes_));
}
}

TEST_F(GetDataReaderQoSTest, infinite_duration_conversions)
{
qos_profile_.lifespan = RMW_DURATION_INFINITE;
qos_profile_.deadline = RMW_DURATION_INFINITE;
qos_profile_.liveliness_lease_duration = RMW_DURATION_INFINITE;
EXPECT_TRUE(get_datareader_qos(qos_profile_, subscriber_attributes_));
EXPECT_EQ(subscriber_attributes_.qos.m_lifespan.duration, InfiniteDuration);
EXPECT_EQ(subscriber_attributes_.qos.m_deadline.period, InfiniteDuration);
EXPECT_EQ(subscriber_attributes_.qos.m_liveliness.lease_duration, InfiniteDuration);
}

TEST_F(GetDataWriterQoSTest, infinite_duration_conversions)
{
qos_profile_.lifespan = RMW_DURATION_INFINITE;
qos_profile_.deadline = RMW_DURATION_INFINITE;
qos_profile_.liveliness_lease_duration = RMW_DURATION_INFINITE;
EXPECT_TRUE(get_datawriter_qos(qos_profile_, publisher_attributes_));
EXPECT_EQ(publisher_attributes_.qos.m_lifespan.duration, InfiniteDuration);
EXPECT_EQ(publisher_attributes_.qos.m_deadline.period, InfiniteDuration);
EXPECT_EQ(publisher_attributes_.qos.m_liveliness.lease_duration, InfiniteDuration);
}