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 <fastdds/dds/core/policy/QosPolicies.hpp>
20 #include <fastdds/dds/publisher/qos/DataWriterQos.hpp>
21 #include <fastdds/dds/subscriber/qos/DataReaderQos.hpp>
22 #include <fastdds/dds/topic/qos/TopicQos.hpp>
23 
24 #include <fastrtps/qos/QosPolicies.h>
25 
26 #include "rmw/rmw.h"
27 
29 
31 bool
32 is_valid_qos(const rmw_qos_profile_t & qos_policies);
33 
35 bool
37  const rmw_qos_profile_t & qos_policies,
38  eprosima::fastdds::dds::DataReaderQos & reader_qos);
39 
41 bool
43  const rmw_qos_profile_t & qos_policies,
44  eprosima::fastdds::dds::DataWriterQos & writer_qos);
45 
47 bool
49  const rmw_qos_profile_t & qos_policies,
50  eprosima::fastdds::dds::TopicQos & topic_qos);
51 
54 dds_duration_to_rmw(const eprosima::fastrtps::Duration_t & duration);
55 
56 /*
57  * Converts the DDS QOS Policy; of type DataWriterQos or DataReaderQos into rmw_qos_profile_t.
58  *
59  * \param[in] dds_qos of type DataWriterQos or DataReaderQos
60  * \param[out] qos the equivalent of the data in dds_qos as a 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.reliability().kind) {
69  case eprosima::fastdds::dds::BEST_EFFORT_RELIABILITY_QOS:
71  break;
72  case eprosima::fastdds::dds::RELIABLE_RELIABILITY_QOS:
74  break;
75  default:
76  qos->reliability = RMW_QOS_POLICY_RELIABILITY_UNKNOWN;
77  break;
78  }
79 
80  switch (dds_qos.durability().kind) {
81  case eprosima::fastdds::dds::TRANSIENT_LOCAL_DURABILITY_QOS:
83  break;
84  case eprosima::fastdds::dds::VOLATILE_DURABILITY_QOS:
86  break;
87  default:
88  qos->durability = RMW_QOS_POLICY_DURABILITY_UNKNOWN;
89  break;
90  }
91 
92  qos->deadline = dds_duration_to_rmw(dds_qos.deadline().period);
93  qos->lifespan = dds_duration_to_rmw(dds_qos.lifespan().duration);
94 
95  switch (dds_qos.liveliness().kind) {
96  case eprosima::fastdds::dds::AUTOMATIC_LIVELINESS_QOS:
98  break;
99  case eprosima::fastdds::dds::MANUAL_BY_TOPIC_LIVELINESS_QOS:
101  break;
102  default:
103  qos->liveliness = RMW_QOS_POLICY_LIVELINESS_UNKNOWN;
104  break;
105  }
106 
107  qos->liveliness_lease_duration = dds_duration_to_rmw(dds_qos.liveliness().lease_duration);
108 
109  switch (dds_qos.history().kind) {
110  case eprosima::fastdds::dds::KEEP_LAST_HISTORY_QOS:
112  break;
113  case eprosima::fastdds::dds::KEEP_ALL_HISTORY_QOS:
115  break;
116  default:
117  qos->history = RMW_QOS_POLICY_HISTORY_UNKNOWN;
118  break;
119  }
120  qos->depth = static_cast<size_t>(dds_qos.history().depth);
121 }
122 
123 /*
124  * Converts the RTPS QOS Policy; of type WriterQos or ReaderQos into rmw_qos_profile_t.
125  * Since WriterQos or ReaderQos do not have information about history and depth,
126  * these values are not set by this function.
127  *
128  * \param[in] rtps_qos of type WriterQos or ReaderQos
129  * \param[out] qos the equivalent of the data in rtps_qos as a rmw_qos_profile_t
130  */
131 template<typename RTPSQoSPolicyT>
132 void
134  const RTPSQoSPolicyT & rtps_qos,
135  rmw_qos_profile_t * qos)
136 {
137  switch (rtps_qos.m_reliability.kind) {
138  case eprosima::fastrtps::BEST_EFFORT_RELIABILITY_QOS:
140  break;
141  case eprosima::fastrtps::RELIABLE_RELIABILITY_QOS:
143  break;
144  default:
145  qos->reliability = RMW_QOS_POLICY_RELIABILITY_UNKNOWN;
146  break;
147  }
148 
149  switch (rtps_qos.m_durability.kind) {
150  case eprosima::fastrtps::TRANSIENT_LOCAL_DURABILITY_QOS:
152  break;
153  case eprosima::fastrtps::VOLATILE_DURABILITY_QOS:
155  break;
156  default:
157  qos->durability = RMW_QOS_POLICY_DURABILITY_UNKNOWN;
158  break;
159  }
160 
161  qos->deadline = dds_duration_to_rmw(rtps_qos.m_deadline.period);
162  qos->lifespan = dds_duration_to_rmw(rtps_qos.m_lifespan.duration);
163 
164  switch (rtps_qos.m_liveliness.kind) {
165  case eprosima::fastrtps::AUTOMATIC_LIVELINESS_QOS:
167  break;
168  case eprosima::fastrtps::MANUAL_BY_TOPIC_LIVELINESS_QOS:
170  break;
171  default:
172  qos->liveliness = RMW_QOS_POLICY_LIVELINESS_UNKNOWN;
173  break;
174  }
175  qos->liveliness_lease_duration = dds_duration_to_rmw(rtps_qos.m_liveliness.lease_duration);
176 }
177 
178 extern template RMW_FASTRTPS_SHARED_CPP_PUBLIC
179 void dds_qos_to_rmw_qos<eprosima::fastdds::dds::DataWriterQos>(
180  const eprosima::fastdds::dds::DataWriterQos & dds_qos,
181  rmw_qos_profile_t * qos);
182 
183 extern template RMW_FASTRTPS_SHARED_CPP_PUBLIC
184 void dds_qos_to_rmw_qos<eprosima::fastdds::dds::DataReaderQos>(
185  const eprosima::fastdds::dds::DataReaderQos & dds_qos,
186  rmw_qos_profile_t * qos);
187 
188 
189 template<typename AttributeT>
190 void
192  const AttributeT & dds_qos,
193  rmw_qos_profile_t * qos);
194 
195 extern template RMW_FASTRTPS_SHARED_CPP_PUBLIC
196 void
197 dds_attributes_to_rmw_qos<eprosima::fastrtps::PublisherAttributes>(
198  const eprosima::fastrtps::PublisherAttributes & dds_qos,
199  rmw_qos_profile_t * qos);
200 
201 extern template RMW_FASTRTPS_SHARED_CPP_PUBLIC
202 void
203 dds_attributes_to_rmw_qos<eprosima::fastrtps::SubscriberAttributes>(
204  const eprosima::fastrtps::SubscriberAttributes & dds_qos,
205  rmw_qos_profile_t * qos);
206 
207 #endif // RMW_FASTRTPS_SHARED_CPP__QOS_HPP_
get_datareader_qos
bool get_datareader_qos(const rmw_qos_profile_t &qos_policies, eprosima::fastdds::dds::DataReaderQos &reader_qos)
RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
RMW_QOS_POLICY_HISTORY_KEEP_ALL
RMW_QOS_POLICY_HISTORY_KEEP_ALL
RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
rmw_time_t
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
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::history
enum rmw_qos_history_policy_t history
get_topic_qos
bool get_topic_qos(const rmw_qos_profile_t &qos_policies, eprosima::fastdds::dds::TopicQos &topic_qos)
rmw_qos_profile_t::liveliness_lease_duration
struct rmw_time_t liveliness_lease_duration
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
dds_duration_to_rmw
rmw_time_t dds_duration_to_rmw(const eprosima::fastrtps::Duration_t &duration)
RMW_QOS_POLICY_RELIABILITY_RELIABLE
RMW_QOS_POLICY_RELIABILITY_RELIABLE
rmw_qos_profile_t
rtps_qos_to_rmw_qos
void rtps_qos_to_rmw_qos(const RTPSQoSPolicyT &rtps_qos, rmw_qos_profile_t *qos)
Definition: qos.hpp:133
RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC
RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC
get_datawriter_qos
bool get_datawriter_qos(const rmw_qos_profile_t &qos_policies, eprosima::fastdds::dds::DataWriterQos &writer_qos)
RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL
RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL
RMW_QOS_POLICY_DURABILITY_VOLATILE
RMW_QOS_POLICY_DURABILITY_VOLATILE
rmw_qos_profile_t::depth
size_t depth
RMW_QOS_POLICY_HISTORY_KEEP_LAST
RMW_QOS_POLICY_HISTORY_KEEP_LAST