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 #287

Merged
merged 3 commits into from
Jun 12, 2019
Merged
Show file tree
Hide file tree
Changes from 1 commit
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 @@ -28,6 +28,10 @@ class PublisherAttributes;
} // namespace fastrtps
} // namespace eprosima

RMW_FASTRTPS_SHARED_CPP_PUBLIC
bool
is_valid_qos(const rmw_qos_profile_t & qos_policies);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

any reason for moving this declaration?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I felt it would be more consistent with the rest of the rmw implementations that the dds_qos_to_rmw_qos() follows get_datareader_qos(). is_valid_qos() is also the first function among the ones declared here to be called in a normal program flow.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sounds good


RMW_FASTRTPS_SHARED_CPP_PUBLIC
bool
get_datareader_qos(
Expand All @@ -40,8 +44,10 @@ get_datawriter_qos(
const rmw_qos_profile_t & qos_policies,
eprosima::fastrtps::PublisherAttributes & pattr);

RMW_FASTRTPS_SHARED_CPP_PUBLIC
bool
is_valid_qos(const rmw_qos_profile_t & qos_policies);
template<typename AttributeT>
void
dds_qos_to_rmw_qos(
const AttributeT & dds_qos,
rmw_qos_profile_t * qos);

#endif // RMW_FASTRTPS_SHARED_CPP__QOS_HPP_
75 changes: 75 additions & 0 deletions rmw_fastrtps_shared_cpp/src/qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,3 +169,78 @@ is_valid_qos(const rmw_qos_profile_t & qos_policies)
}
return true;
}

template<typename AttributeT>
void
dds_qos_to_rmw_qos(
const AttributeT & dds_qos,
rmw_qos_profile_t * qos)
{
switch (dds_qos.topic.historyQos.kind) {
case eprosima::fastrtps::KEEP_LAST_HISTORY_QOS:
qos->history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
break;
case eprosima::fastrtps::KEEP_ALL_HISTORY_QOS:
qos->history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
break;
default:
qos->history = RMW_QOS_POLICY_HISTORY_UNKNOWN;
break;
}
qos->depth = static_cast<size_t>(dds_qos.topic.historyQos.depth);

switch (dds_qos.qos.m_reliability.kind) {
case eprosima::fastrtps::BEST_EFFORT_RELIABILITY_QOS:
qos->reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
break;
case eprosima::fastrtps::RELIABLE_RELIABILITY_QOS:
qos->reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
break;
default:
qos->reliability = RMW_QOS_POLICY_RELIABILITY_UNKNOWN;
break;
}

switch (dds_qos.qos.m_durability.kind) {
case eprosima::fastrtps::TRANSIENT_LOCAL_DURABILITY_QOS:
qos->durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
break;
case eprosima::fastrtps::VOLATILE_DURABILITY_QOS:
qos->durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
break;
default:
qos->durability = RMW_QOS_POLICY_DURABILITY_UNKNOWN;
break;
}

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

qos->lifespan.sec = dds_qos.qos.m_lifespan.duration.seconds;
qos->lifespan.nsec = dds_qos.qos.m_lifespan.duration.nanosec;

switch (dds_qos.qos.m_liveliness.kind) {
case eprosima::fastrtps::AUTOMATIC_LIVELINESS_QOS:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
break;
case eprosima::fastrtps::MANUAL_BY_PARTICIPANT_LIVELINESS_QOS:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE;
break;
case eprosima::fastrtps::MANUAL_BY_TOPIC_LIVELINESS_QOS:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC;
break;
default:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_UNKNOWN;
break;
}
qos->liveliness_lease_duration.sec = dds_qos.qos.m_liveliness.lease_duration.seconds;
qos->liveliness_lease_duration.nsec = dds_qos.qos.m_liveliness.lease_duration.nanosec;
}

template void dds_qos_to_rmw_qos<eprosima::fastrtps::PublisherAttributes>(
const eprosima::fastrtps::PublisherAttributes & dds_qos,
rmw_qos_profile_t * qos);

template void dds_qos_to_rmw_qos<eprosima::fastrtps::SubscriberAttributes>(
const eprosima::fastrtps::SubscriberAttributes & dds_qos,
rmw_qos_profile_t * qos);
60 changes: 1 addition & 59 deletions rmw_fastrtps_shared_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,65 +146,7 @@ __rmw_publisher_get_actual_qos(
const eprosima::fastrtps::PublisherAttributes & attributes =
fastrtps_pub->getAttributes();

switch (attributes.topic.historyQos.kind) {
case eprosima::fastrtps::KEEP_LAST_HISTORY_QOS:
qos->history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
break;
case eprosima::fastrtps::KEEP_ALL_HISTORY_QOS:
qos->history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
break;
default:
qos->history = RMW_QOS_POLICY_HISTORY_UNKNOWN;
break;
}
qos->depth = static_cast<size_t>(attributes.topic.historyQos.depth);

switch (attributes.qos.m_reliability.kind) {
case eprosima::fastrtps::BEST_EFFORT_RELIABILITY_QOS:
qos->reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
break;
case eprosima::fastrtps::RELIABLE_RELIABILITY_QOS:
qos->reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
break;
default:
qos->reliability = RMW_QOS_POLICY_RELIABILITY_UNKNOWN;
break;
}

switch (attributes.qos.m_durability.kind) {
case eprosima::fastrtps::TRANSIENT_LOCAL_DURABILITY_QOS:
qos->durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
break;
case eprosima::fastrtps::VOLATILE_DURABILITY_QOS:
qos->durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
break;
default:
qos->durability = RMW_QOS_POLICY_DURABILITY_UNKNOWN;
break;
}

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

qos->lifespan.sec = attributes.qos.m_lifespan.duration.seconds;
qos->lifespan.nsec = attributes.qos.m_lifespan.duration.nanosec;

switch (attributes.qos.m_liveliness.kind) {
case eprosima::fastrtps::AUTOMATIC_LIVELINESS_QOS:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
break;
case eprosima::fastrtps::MANUAL_BY_PARTICIPANT_LIVELINESS_QOS:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE;
break;
case eprosima::fastrtps::MANUAL_BY_TOPIC_LIVELINESS_QOS:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC;
break;
default:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_UNKNOWN;
break;
}
qos->liveliness_lease_duration.sec = attributes.qos.m_liveliness.lease_duration.seconds;
qos->liveliness_lease_duration.nsec = attributes.qos.m_liveliness.lease_duration.nanosec;
dds_qos_to_rmw_qos(attributes, qos);

return RMW_RET_OK;
}
Expand Down
61 changes: 1 addition & 60 deletions rmw_fastrtps_shared_cpp/src/rmw_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,67 +125,8 @@ __rmw_subscription_get_actual_qos(
const eprosima::fastrtps::SubscriberAttributes & attributes =
fastrtps_sub->getAttributes();

switch (attributes.topic.historyQos.kind) {
case eprosima::fastrtps::KEEP_LAST_HISTORY_QOS:
qos->history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
break;
case eprosima::fastrtps::KEEP_ALL_HISTORY_QOS:
qos->history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
break;
default:
qos->history = RMW_QOS_POLICY_HISTORY_UNKNOWN;
break;
}
qos->depth = static_cast<size_t>(attributes.topic.historyQos.depth);

switch (attributes.qos.m_reliability.kind) {
case eprosima::fastrtps::BEST_EFFORT_RELIABILITY_QOS:
qos->reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
break;
case eprosima::fastrtps::RELIABLE_RELIABILITY_QOS:
qos->reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
break;
default:
qos->reliability = RMW_QOS_POLICY_RELIABILITY_UNKNOWN;
break;
}

switch (attributes.qos.m_durability.kind) {
case eprosima::fastrtps::TRANSIENT_LOCAL_DURABILITY_QOS:
qos->durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
break;
case eprosima::fastrtps::VOLATILE_DURABILITY_QOS:
qos->durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
break;
default:
qos->durability = RMW_QOS_POLICY_DURABILITY_UNKNOWN;
break;
}

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

qos->lifespan.sec = attributes.qos.m_lifespan.duration.seconds;
qos->lifespan.nsec = attributes.qos.m_lifespan.duration.nanosec;

switch (attributes.qos.m_liveliness.kind) {
case eprosima::fastrtps::AUTOMATIC_LIVELINESS_QOS:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
break;
case eprosima::fastrtps::MANUAL_BY_PARTICIPANT_LIVELINESS_QOS:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE;
break;
case eprosima::fastrtps::MANUAL_BY_TOPIC_LIVELINESS_QOS:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC;
break;
default:
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_UNKNOWN;
break;
}
qos->liveliness_lease_duration.sec = attributes.qos.m_liveliness.lease_duration.seconds;
qos->liveliness_lease_duration.nsec = attributes.qos.m_liveliness.lease_duration.nanosec;
dds_qos_to_rmw_qos(attributes, qos);

return RMW_RET_OK;
}

} // namespace rmw_fastrtps_shared_cpp