rmw_fastrtps_shared_cpp  master
Code shared on static and dynamic type support of rmw_fastrtps_cpp.
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
qos.hpp
Go to the documentation of this file.
1 // Copyright 2019 Open Source Robotics Foundation, Inc.
2 // Copyright 2016-2018 Proyectos y Sistemas de Mantenimiento SL (eProsima).
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef RMW_FASTRTPS_SHARED_CPP__QOS_HPP_
17 #define RMW_FASTRTPS_SHARED_CPP__QOS_HPP_
18 
19 #include "fastrtps/attributes/PublisherAttributes.h"
20 #include "fastrtps/attributes/SubscriberAttributes.h"
21 #include "fastrtps/qos/QosPolicies.h"
22 #include "fastrtps/qos/ReaderQos.h"
23 #include "fastrtps/qos/WriterQos.h"
24 
25 #include "rmw/rmw.h"
26 
28 
29 namespace eprosima
30 {
31 namespace fastrtps
32 {
33 class SubscriberAttributes;
34 class PublisherAttributes;
35 } // namespace fastrtps
36 } // namespace eprosima
37 
39 bool
40 is_valid_qos(const rmw_qos_profile_t & qos_policies);
41 
43 bool
45  const rmw_qos_profile_t & qos_policies,
46  eprosima::fastrtps::SubscriberAttributes & sattr);
47 
49 bool
51  const rmw_qos_profile_t & qos_policies,
52  eprosima::fastrtps::PublisherAttributes & pattr);
53 
54 /*
55  * Converts the low-level QOS Policy; of type WriterQos or ReaderQos into rmw_qos_profile_t.
56  * Since WriterQos or ReaderQos does not have information about history and depth, these values are not set
57  * by this function.
58  *
59  * \param[in] dds_qos of type WriterQos or ReaderQos
60  * \param[out] qos the equivalent of the data in WriterQos or ReaderQos in rmw_qos_profile_t
61  */
62 template<typename DDSQoSPolicyT>
63 void
65  const DDSQoSPolicyT & dds_qos,
66  rmw_qos_profile_t * qos)
67 {
68  switch (dds_qos.m_reliability.kind) {
69  case eprosima::fastrtps::BEST_EFFORT_RELIABILITY_QOS:
71  break;
72  case eprosima::fastrtps::RELIABLE_RELIABILITY_QOS:
74  break;
75  default:
76  qos->reliability = RMW_QOS_POLICY_RELIABILITY_UNKNOWN;
77  break;
78  }
79 
80  switch (dds_qos.m_durability.kind) {
81  case eprosima::fastrtps::TRANSIENT_LOCAL_DURABILITY_QOS:
83  break;
84  case eprosima::fastrtps::VOLATILE_DURABILITY_QOS:
86  break;
87  default:
88  qos->durability = RMW_QOS_POLICY_DURABILITY_UNKNOWN;
89  break;
90  }
91 
92  qos->deadline.sec = dds_qos.m_deadline.period.seconds;
93  qos->deadline.nsec = dds_qos.m_deadline.period.nanosec;
94 
95  qos->lifespan.sec = dds_qos.m_lifespan.duration.seconds;
96  qos->lifespan.nsec = dds_qos.m_lifespan.duration.nanosec;
97 
98  switch (dds_qos.m_liveliness.kind) {
99  case eprosima::fastrtps::AUTOMATIC_LIVELINESS_QOS:
101  break;
102  case eprosima::fastrtps::MANUAL_BY_TOPIC_LIVELINESS_QOS:
104  break;
105  default:
106  qos->liveliness = RMW_QOS_POLICY_LIVELINESS_UNKNOWN;
107  break;
108  }
109  qos->liveliness_lease_duration.sec = dds_qos.m_liveliness.lease_duration.seconds;
110  qos->liveliness_lease_duration.nsec = dds_qos.m_liveliness.lease_duration.nanosec;
111 }
112 
113 template<typename AttributeT>
114 void
116  const AttributeT & dds_qos,
117  rmw_qos_profile_t * qos);
118 
119 extern template RMW_FASTRTPS_SHARED_CPP_PUBLIC
120 void
121 dds_attributes_to_rmw_qos<eprosima::fastrtps::PublisherAttributes>(
122  const eprosima::fastrtps::PublisherAttributes & dds_qos,
123  rmw_qos_profile_t * qos);
124 
125 extern template RMW_FASTRTPS_SHARED_CPP_PUBLIC
126 void
127 dds_attributes_to_rmw_qos<eprosima::fastrtps::SubscriberAttributes>(
128  const eprosima::fastrtps::SubscriberAttributes & dds_qos,
129  rmw_qos_profile_t * qos);
130 
131 #endif // RMW_FASTRTPS_SHARED_CPP__QOS_HPP_
RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
get_datawriter_qos
bool get_datawriter_qos(const rmw_qos_profile_t &qos_policies, eprosima::fastrtps::PublisherAttributes &pattr)
rmw_time_t::nsec
uint64_t nsec
RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
rmw.h
is_valid_qos
bool is_valid_qos(const rmw_qos_profile_t &qos_policies)
RMW_FASTRTPS_SHARED_CPP_PUBLIC
#define RMW_FASTRTPS_SHARED_CPP_PUBLIC
Definition: visibility_control.h:50
dds_qos_to_rmw_qos
void dds_qos_to_rmw_qos(const DDSQoSPolicyT &dds_qos, rmw_qos_profile_t *qos)
Definition: qos.hpp:64
rmw_qos_profile_t::durability
enum rmw_qos_durability_policy_t durability
get_datareader_qos
bool get_datareader_qos(const rmw_qos_profile_t &qos_policies, eprosima::fastrtps::SubscriberAttributes &sattr)
dds_attributes_to_rmw_qos
void dds_attributes_to_rmw_qos(const AttributeT &dds_qos, rmw_qos_profile_t *qos)
rmw_qos_profile_t::deadline
struct rmw_time_t deadline
rmw_qos_profile_t::lifespan
struct rmw_time_t lifespan
rmw_qos_profile_t::liveliness_lease_duration
struct rmw_time_t liveliness_lease_duration
rmw_time_t::sec
uint64_t sec
rmw_qos_profile_t::liveliness
enum rmw_qos_liveliness_policy_t liveliness
visibility_control.h
rmw_qos_profile_t::reliability
enum rmw_qos_reliability_policy_t reliability
RMW_QOS_POLICY_RELIABILITY_RELIABLE
RMW_QOS_POLICY_RELIABILITY_RELIABLE
rmw_qos_profile_t
RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC
RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC
RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL
RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL
eprosima
Definition: qos.hpp:29
RMW_QOS_POLICY_DURABILITY_VOLATILE
RMW_QOS_POLICY_DURABILITY_VOLATILE