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

Use RMW_DURATION_INFINITE constant #512

Closed
Closed
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 rmw_fastrtps_cpp/src/rmw_wait.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ rmw_wait(
rmw_clients_t * clients,
rmw_events_t * events,
rmw_wait_set_t * wait_set,
const rmw_time_t * wait_timeout)
rmw_duration_t wait_timeout)
{
return rmw_fastrtps_shared_cpp::__rmw_wait(
eprosima_fastrtps_identifier, subscriptions, guard_conditions, services, clients, events,
Expand Down
2 changes: 1 addition & 1 deletion rmw_fastrtps_dynamic_cpp/src/rmw_wait.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ rmw_wait(
rmw_clients_t * clients,
rmw_events_t * events,
rmw_wait_set_t * wait_set,
const rmw_time_t * wait_timeout)
rmw_duration_t wait_timeout)
{
return rmw_fastrtps_shared_cpp::__rmw_wait(
eprosima_fastrtps_identifier, subscriptions, guard_conditions, services, clients, events,
Expand Down
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_duration_t
fastrtps_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 = fastrtps_duration_to_rmw(dds_qos.m_deadline.period);
qos->lifespan = fastrtps_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 = fastrtps_duration_to_rmw(dds_qos.m_liveliness.lease_duration);
}

template<typename AttributeT>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -362,7 +362,7 @@ __rmw_wait(
rmw_clients_t * clients,
rmw_events_t * events,
rmw_wait_set_t * wait_set,
const rmw_time_t * wait_timeout);
rmw_duration_t wait_timeout);

RMW_FASTRTPS_SHARED_CPP_PUBLIC
rmw_wait_set_t *
Expand Down
2 changes: 1 addition & 1 deletion rmw_fastrtps_shared_cpp/src/listener_thread.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ node_listener(rmw_context_t * context)
nullptr,
nullptr,
wait_set,
nullptr))
-1))
{
TERMINATE_THREAD("rmw_wait failed");
}
Expand Down
34 changes: 21 additions & 13 deletions rmw_fastrtps_shared_cpp/src/qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,23 +20,21 @@
#include "fastrtps/attributes/SubscriberAttributes.h"

#include "rmw/error_handling.h"
#include "rmw_dds_common/time_utils.hpp"

static
eprosima::fastrtps::Duration_t
rmw_time_to_fastrtps(const rmw_time_t & time)
rmw_duration_to_fastrtps(const rmw_duration_t duration)
{
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),
static_cast<uint32_t>(clamped_time.nsec));
static_cast<int32_t>(RCUTILS_NS_TO_S(duration)),
static_cast<uint32_t>(duration % RCUTILS_S_TO_NS(1)));
}

static
bool
is_time_default(const rmw_time_t & time)
is_duration_default(const rmw_duration_t & duration)
{
return time.sec == 0 && time.nsec == 0;
return duration == 0 || duration == RMW_DURATION_INFINITE;
}

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

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

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

switch (qos_policies.liveliness) {
Expand All @@ -122,9 +120,9 @@ 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_duration_default(qos_policies.liveliness_lease_duration)) {
entity_qos.m_liveliness.lease_duration =
rmw_time_to_fastrtps(qos_policies.liveliness_lease_duration);
rmw_duration_to_fastrtps(qos_policies.liveliness_lease_duration);

// Docs suggest setting no higher than 0.7 * lease_duration, choosing 2/3 to give safe buffer.
// See doc at https://github.com/eProsima/Fast-RTPS/blob/
Expand Down Expand Up @@ -158,6 +156,16 @@ is_valid_qos(const rmw_qos_profile_t & /* qos_policies */)
return true;
}

rmw_duration_t
fastrtps_duration_to_rmw(const eprosima::fastrtps::Duration_t & duration)
{
if (duration == eprosima::fastrtps::rtps::c_RTPSTimeInfinite) {
return RMW_DURATION_INFINITE;
} else {
return RCUTILS_S_TO_NS(duration.seconds) + duration.nanosec;
}
}

template<typename AttributeT>
void
dds_attributes_to_rmw_qos(
Expand Down
12 changes: 5 additions & 7 deletions rmw_fastrtps_shared_cpp/src/rmw_wait.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ __rmw_wait(
rmw_clients_t * clients,
rmw_events_t * events,
rmw_wait_set_t * wait_set,
const rmw_time_t * wait_timeout)
rmw_duration_t wait_timeout)
{
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RMW_RET_INVALID_ARGUMENT);
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
Expand Down Expand Up @@ -174,13 +174,11 @@ __rmw_wait(

bool timeout = false;
if (!hasData) {
if (!wait_timeout) {
if (wait_timeout < 0) {
conditionVariable->wait(lock, predicate);
} else if (wait_timeout->sec > 0 || wait_timeout->nsec > 0) {
auto n = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::seconds(wait_timeout->sec));
n += std::chrono::nanoseconds(wait_timeout->nsec);
timeout = !conditionVariable->wait_for(lock, n, predicate);
} else if (wait_timeout > 0) {
timeout = !conditionVariable->wait_for(
lock, std::chrono::nanoseconds(wait_timeout), predicate);
} else {
timeout = true;
}
Expand Down
24 changes: 12 additions & 12 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 @@ -65,23 +65,23 @@ TEST_F(DDSAttributesToRMWQosTest, test_publisher_liveliness_conversion) {

TEST_F(DDSAttributesToRMWQosTest, test_publisher_liveliness_lease_duration_conversion) {
publisher_attributes_.qos.m_liveliness.lease_duration = {8, 78901234};
rmw_duration_t expected = RCUTILS_S_TO_NS(8) + 78901234;
dds_attributes_to_rmw_qos(publisher_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.liveliness_lease_duration.sec, 8u);
EXPECT_EQ(qos_profile_.liveliness_lease_duration.nsec, 78901234u);
EXPECT_EQ(qos_profile_.liveliness_lease_duration, expected);
}

TEST_F(DDSAttributesToRMWQosTest, test_publisher_deadline_conversion) {
publisher_attributes_.qos.m_deadline.period = {12, 1234};
rmw_duration_t expected = RCUTILS_S_TO_NS(12) + 1234;
dds_attributes_to_rmw_qos(publisher_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.deadline.sec, 12u);
EXPECT_EQ(qos_profile_.deadline.nsec, 1234u);
EXPECT_EQ(qos_profile_.deadline, expected);
}

TEST_F(DDSAttributesToRMWQosTest, test_publisher_lifespan_conversion) {
publisher_attributes_.qos.m_lifespan.duration = {19, 5432};
rmw_duration_t expected = RCUTILS_S_TO_NS(19) + 5432;
dds_attributes_to_rmw_qos(publisher_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.lifespan.sec, 19u);
EXPECT_EQ(qos_profile_.lifespan.nsec, 5432u);
EXPECT_EQ(qos_profile_.lifespan, expected);
}


Expand Down Expand Up @@ -118,21 +118,21 @@ TEST_F(DDSAttributesToRMWQosTest, test_subscriber_liveliness_conversion) {

TEST_F(DDSAttributesToRMWQosTest, test_subscriber_liveliness_lease_duration_conversion) {
subscriber_attributes_.qos.m_liveliness.lease_duration = {80, 34567};
rmw_duration_t expected = RCUTILS_S_TO_NS(80) + 34567;
dds_attributes_to_rmw_qos(subscriber_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.liveliness_lease_duration.sec, 80u);
EXPECT_EQ(qos_profile_.liveliness_lease_duration.nsec, 34567u);
EXPECT_EQ(qos_profile_.liveliness_lease_duration, expected);
}

TEST_F(DDSAttributesToRMWQosTest, test_subscriber_deadline_conversion) {
subscriber_attributes_.qos.m_deadline.period = {1, 3324};
rmw_duration_t expected = RCUTILS_S_TO_NS(1) + 3324;
dds_attributes_to_rmw_qos(subscriber_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.deadline.sec, 1u);
EXPECT_EQ(qos_profile_.deadline.nsec, 3324u);
EXPECT_EQ(qos_profile_.deadline, expected);
}

TEST_F(DDSAttributesToRMWQosTest, test_subscriber_lifespan_conversion) {
subscriber_attributes_.qos.m_lifespan.duration = {9, 432};
rmw_duration_t expected = RCUTILS_S_TO_NS(9) + 432;
dds_attributes_to_rmw_qos(subscriber_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.lifespan.sec, 9u);
EXPECT_EQ(qos_profile_.lifespan.nsec, 432u);
EXPECT_EQ(qos_profile_.lifespan, expected);
}
18 changes: 6 additions & 12 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 @@ -67,13 +67,10 @@ TEST_F(GetDataReaderQoSTest, nominal_conversion) {
qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
qos_profile_.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
qos_profile_.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
qos_profile_.lifespan.sec = 0u;
qos_profile_.lifespan.nsec = 500000000u;
qos_profile_.deadline.sec = 0u;
qos_profile_.deadline.nsec = 100000000u;
qos_profile_.lifespan = 500000000u;
qos_profile_.deadline = 100000000u;
qos_profile_.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
qos_profile_.liveliness_lease_duration.sec = 10u;
qos_profile_.liveliness_lease_duration.nsec = 0u;
qos_profile_.liveliness_lease_duration = RCUTILS_S_TO_NS(10u);

EXPECT_TRUE(get_datareader_qos(qos_profile_, subscriber_attributes_));

Expand Down Expand Up @@ -165,13 +162,10 @@ TEST_F(GetDataWriterQoSTest, nominal_conversion) {
qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
qos_profile_.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
qos_profile_.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
qos_profile_.lifespan.sec = 0u;
qos_profile_.lifespan.nsec = 500000000u;
qos_profile_.deadline.sec = 0u;
qos_profile_.deadline.nsec = 100000000u;
qos_profile_.lifespan = 500000000u;
qos_profile_.deadline = 100000000u;
qos_profile_.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
qos_profile_.liveliness_lease_duration.sec = 10u;
qos_profile_.liveliness_lease_duration.nsec = 0u;
qos_profile_.liveliness_lease_duration = RCUTILS_S_TO_NS(10u);

EXPECT_TRUE(get_datawriter_qos(qos_profile_, publisher_attributes_));

Expand Down