Skip to content

Commit

Permalink
Added new functions which can be used to get rmw_qos_profile_t from W…
Browse files Browse the repository at this point in the history
…riterQos and ReaderQos (#328)

Signed-off-by: Jaison Titus <[email protected]>
  • Loading branch information
jaisontj authored and ivanpauno committed Oct 14, 2019
1 parent 394ddbd commit 455d214
Show file tree
Hide file tree
Showing 5 changed files with 233 additions and 47 deletions.
1 change: 1 addition & 0 deletions rmw_fastrtps_shared_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,7 @@ ament_export_dependencies(rmw)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
add_subdirectory(test)
endif()

ament_package(
Expand Down
49 changes: 2 additions & 47 deletions rmw_fastrtps_shared_cpp/src/qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <limits>

#include "qos_converter.hpp"
#include "rmw_fastrtps_shared_cpp/qos.hpp"

#include "fastrtps/attributes/PublisherAttributes.h"
Expand Down Expand Up @@ -181,53 +182,7 @@ dds_attributes_to_rmw_qos(
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;
dds_qos_to_rmw_qos(dds_qos.qos, qos);
}

template
Expand Down
86 changes: 86 additions & 0 deletions rmw_fastrtps_shared_cpp/src/qos_converter.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
// Copyright 2016-2018 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.


#ifndef QOS_CONVERTER_HPP_
#define QOS_CONVERTER_HPP_

#include "rmw/types.h"

#include "fastrtps/qos/WriterQos.h"
#include "fastrtps/qos/ReaderQos.h"

/*
* 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
* by this function.
*
* \param[in] dds_qos of type WriterQos or ReaderQos
* \param[out] qos the equivalent of the data in WriterQos or ReaderQos in rmw_qos_profile_t
*/
template<typename DDSQoSPolicyT>
void
dds_qos_to_rmw_qos(
const DDSQoSPolicyT & dds_qos,
rmw_qos_profile_t * qos)
{
switch (dds_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.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.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;

switch (dds_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.m_liveliness.lease_duration.seconds;
qos->liveliness_lease_duration.nsec = dds_qos.m_liveliness.lease_duration.nanosec;
}

#endif // QOS_CONVERTER_HPP_
6 changes: 6 additions & 0 deletions rmw_fastrtps_shared_cpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
find_package(ament_cmake_gtest REQUIRED)
ament_add_gtest(test_dds_attributes_to_rmw_qos test_dds_attributes_to_rmw_qos.cpp)
if(TARGET test_dds_attributes_to_rmw_qos)
ament_target_dependencies(test_dds_attributes_to_rmw_qos)
target_link_libraries(test_dds_attributes_to_rmw_qos ${PROJECT_NAME})
endif()
138 changes: 138 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
@@ -0,0 +1,138 @@
// Copyright 2017 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <tuple>

#include "gtest/gtest.h"

#include "fastrtps/attributes/PublisherAttributes.h"
#include "fastrtps/attributes/SubscriberAttributes.h"

#include "rmw_fastrtps_shared_cpp/qos.hpp"

using eprosima::fastrtps::PublisherAttributes;
using eprosima::fastrtps::SubscriberAttributes;

class DDSAttributesToRMWQosTest : public ::testing::Test
{
protected:
rmw_qos_profile_t qos_profile_ {};
PublisherAttributes publisher_attributes_ {};
SubscriberAttributes subscriber_attributes_ {};
};


TEST_F(DDSAttributesToRMWQosTest, test_publisher_depth_conversion) {
publisher_attributes_.topic.historyQos.depth = 0;
dds_attributes_to_rmw_qos(publisher_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.depth, 0u);
}

TEST_F(DDSAttributesToRMWQosTest, test_publisher_history_conversion) {
publisher_attributes_.topic.historyQos.kind = eprosima::fastrtps::KEEP_ALL_HISTORY_QOS;
dds_attributes_to_rmw_qos(publisher_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.history, RMW_QOS_POLICY_HISTORY_KEEP_ALL);
}

TEST_F(DDSAttributesToRMWQosTest, test_publisher_durability_conversion) {
publisher_attributes_.qos.m_durability.kind = eprosima::fastrtps::TRANSIENT_DURABILITY_QOS;
dds_attributes_to_rmw_qos(publisher_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.durability, RMW_QOS_POLICY_DURABILITY_UNKNOWN);
}

TEST_F(DDSAttributesToRMWQosTest, test_publisher_reliability_conversion) {
publisher_attributes_.qos.m_reliability.kind = eprosima::fastrtps::RELIABLE_RELIABILITY_QOS;
dds_attributes_to_rmw_qos(publisher_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
}

TEST_F(DDSAttributesToRMWQosTest, test_publisher_liveliness_conversion) {
publisher_attributes_.qos.m_liveliness.kind = eprosima::fastrtps::MANUAL_BY_TOPIC_LIVELINESS_QOS;
dds_attributes_to_rmw_qos(publisher_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.liveliness, RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC);
}

TEST_F(DDSAttributesToRMWQosTest, test_publisher_liveliness_lease_duration_conversion) {
publisher_attributes_.qos.m_liveliness.lease_duration = {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);
}

TEST_F(DDSAttributesToRMWQosTest, test_publisher_deadline_conversion) {
publisher_attributes_.qos.m_deadline.period = {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);
}

TEST_F(DDSAttributesToRMWQosTest, test_publisher_lifespan_conversion) {
publisher_attributes_.qos.m_lifespan.duration = {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);
}


TEST_F(DDSAttributesToRMWQosTest, test_subscriber_depth_conversion) {
subscriber_attributes_.topic.historyQos.depth = 1;
dds_attributes_to_rmw_qos(subscriber_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.depth, 1u);
}

TEST_F(DDSAttributesToRMWQosTest, test_subscriber_history_conversion) {
subscriber_attributes_.topic.historyQos.kind = eprosima::fastrtps::KEEP_LAST_HISTORY_QOS;
dds_attributes_to_rmw_qos(subscriber_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.history, RMW_QOS_POLICY_HISTORY_KEEP_LAST);
}

TEST_F(DDSAttributesToRMWQosTest, test_subscriber_durability_conversion) {
subscriber_attributes_.qos.m_durability.kind = eprosima::fastrtps::TRANSIENT_LOCAL_DURABILITY_QOS;
dds_attributes_to_rmw_qos(subscriber_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
}

TEST_F(DDSAttributesToRMWQosTest, test_subscriber_reliability_conversion) {
subscriber_attributes_.qos.m_reliability.kind = eprosima::fastrtps::BEST_EFFORT_RELIABILITY_QOS;
dds_attributes_to_rmw_qos(subscriber_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.reliability, RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT);
}

TEST_F(DDSAttributesToRMWQosTest, test_subscriber_liveliness_conversion) {
subscriber_attributes_.qos.m_liveliness.kind =
eprosima::fastrtps::MANUAL_BY_PARTICIPANT_LIVELINESS_QOS;
dds_attributes_to_rmw_qos(subscriber_attributes_, &qos_profile_);
EXPECT_EQ(qos_profile_.liveliness, RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE);
}

TEST_F(DDSAttributesToRMWQosTest, test_subscriber_liveliness_lease_duration_conversion) {
subscriber_attributes_.qos.m_liveliness.lease_duration = {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);
}

TEST_F(DDSAttributesToRMWQosTest, test_subscriber_deadline_conversion) {
subscriber_attributes_.qos.m_deadline.period = {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);
}

TEST_F(DDSAttributesToRMWQosTest, test_subscriber_lifespan_conversion) {
subscriber_attributes_.qos.m_lifespan.duration = {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);
}

0 comments on commit 455d214

Please sign in to comment.