Skip to content

Commit abe500c

Browse files
mm318ivanpauno
authored andcommitted
Implement get_actual_qos() for subscriptions (#287)
Signed-off-by: Miaofei <[email protected]>
1 parent 2a49da4 commit abe500c

File tree

7 files changed

+146
-62
lines changed

7 files changed

+146
-62
lines changed

rmw_fastrtps_cpp/src/rmw_subscription.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -216,6 +216,15 @@ rmw_subscription_count_matched_publishers(
216216
subscription, publisher_count);
217217
}
218218

219+
rmw_ret_t
220+
rmw_subscription_get_actual_qos(
221+
const rmw_subscription_t * subscription,
222+
rmw_qos_profile_t * qos)
223+
{
224+
return rmw_fastrtps_shared_cpp::__rmw_subscription_get_actual_qos(
225+
subscription, qos);
226+
}
227+
219228
rmw_ret_t
220229
rmw_destroy_subscription(rmw_node_t * node, rmw_subscription_t * subscription)
221230
{

rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -212,6 +212,15 @@ rmw_subscription_count_matched_publishers(
212212
subscription, publisher_count);
213213
}
214214

215+
rmw_ret_t
216+
rmw_subscription_get_actual_qos(
217+
const rmw_subscription_t * subscription,
218+
rmw_qos_profile_t * qos)
219+
{
220+
return rmw_fastrtps_shared_cpp::__rmw_subscription_get_actual_qos(
221+
subscription, qos);
222+
}
223+
215224
rmw_ret_t
216225
rmw_destroy_subscription(rmw_node_t * node, rmw_subscription_t * subscription)
217226
{

rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/qos.hpp

Lines changed: 21 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,10 @@ class PublisherAttributes;
2828
} // namespace fastrtps
2929
} // namespace eprosima
3030

31+
RMW_FASTRTPS_SHARED_CPP_PUBLIC
32+
bool
33+
is_valid_qos(const rmw_qos_profile_t & qos_policies);
34+
3135
RMW_FASTRTPS_SHARED_CPP_PUBLIC
3236
bool
3337
get_datareader_qos(
@@ -40,8 +44,22 @@ get_datawriter_qos(
4044
const rmw_qos_profile_t & qos_policies,
4145
eprosima::fastrtps::PublisherAttributes & pattr);
4246

43-
RMW_FASTRTPS_SHARED_CPP_PUBLIC
44-
bool
45-
is_valid_qos(const rmw_qos_profile_t & qos_policies);
47+
template<typename AttributeT>
48+
void
49+
dds_qos_to_rmw_qos(
50+
const AttributeT & dds_qos,
51+
rmw_qos_profile_t * qos);
52+
53+
extern template RMW_FASTRTPS_SHARED_CPP_PUBLIC
54+
void
55+
dds_qos_to_rmw_qos<eprosima::fastrtps::PublisherAttributes>(
56+
const eprosima::fastrtps::PublisherAttributes & dds_qos,
57+
rmw_qos_profile_t * qos);
58+
59+
extern template RMW_FASTRTPS_SHARED_CPP_PUBLIC
60+
void
61+
dds_qos_to_rmw_qos<eprosima::fastrtps::SubscriberAttributes>(
62+
const eprosima::fastrtps::SubscriberAttributes & dds_qos,
63+
rmw_qos_profile_t * qos);
4664

4765
#endif // RMW_FASTRTPS_SHARED_CPP__QOS_HPP_

rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/rmw_common.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -258,6 +258,12 @@ __rmw_subscription_count_matched_publishers(
258258
const rmw_subscription_t * subscription,
259259
size_t * publisher_count);
260260

261+
RMW_FASTRTPS_SHARED_CPP_PUBLIC
262+
rmw_ret_t
263+
__rmw_subscription_get_actual_qos(
264+
const rmw_subscription_t * subscription,
265+
rmw_qos_profile_t * qos);
266+
261267
RMW_FASTRTPS_SHARED_CPP_PUBLIC
262268
rmw_ret_t
263269
__rmw_take(

rmw_fastrtps_shared_cpp/src/qos.cpp

Lines changed: 77 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -169,3 +169,80 @@ is_valid_qos(const rmw_qos_profile_t & qos_policies)
169169
}
170170
return true;
171171
}
172+
173+
template<typename AttributeT>
174+
void
175+
dds_qos_to_rmw_qos(
176+
const AttributeT & dds_qos,
177+
rmw_qos_profile_t * qos)
178+
{
179+
switch (dds_qos.topic.historyQos.kind) {
180+
case eprosima::fastrtps::KEEP_LAST_HISTORY_QOS:
181+
qos->history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
182+
break;
183+
case eprosima::fastrtps::KEEP_ALL_HISTORY_QOS:
184+
qos->history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
185+
break;
186+
default:
187+
qos->history = RMW_QOS_POLICY_HISTORY_UNKNOWN;
188+
break;
189+
}
190+
qos->depth = static_cast<size_t>(dds_qos.topic.historyQos.depth);
191+
192+
switch (dds_qos.qos.m_reliability.kind) {
193+
case eprosima::fastrtps::BEST_EFFORT_RELIABILITY_QOS:
194+
qos->reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
195+
break;
196+
case eprosima::fastrtps::RELIABLE_RELIABILITY_QOS:
197+
qos->reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
198+
break;
199+
default:
200+
qos->reliability = RMW_QOS_POLICY_RELIABILITY_UNKNOWN;
201+
break;
202+
}
203+
204+
switch (dds_qos.qos.m_durability.kind) {
205+
case eprosima::fastrtps::TRANSIENT_LOCAL_DURABILITY_QOS:
206+
qos->durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
207+
break;
208+
case eprosima::fastrtps::VOLATILE_DURABILITY_QOS:
209+
qos->durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
210+
break;
211+
default:
212+
qos->durability = RMW_QOS_POLICY_DURABILITY_UNKNOWN;
213+
break;
214+
}
215+
216+
qos->deadline.sec = dds_qos.qos.m_deadline.period.seconds;
217+
qos->deadline.nsec = dds_qos.qos.m_deadline.period.nanosec;
218+
219+
qos->lifespan.sec = dds_qos.qos.m_lifespan.duration.seconds;
220+
qos->lifespan.nsec = dds_qos.qos.m_lifespan.duration.nanosec;
221+
222+
switch (dds_qos.qos.m_liveliness.kind) {
223+
case eprosima::fastrtps::AUTOMATIC_LIVELINESS_QOS:
224+
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
225+
break;
226+
case eprosima::fastrtps::MANUAL_BY_PARTICIPANT_LIVELINESS_QOS:
227+
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE;
228+
break;
229+
case eprosima::fastrtps::MANUAL_BY_TOPIC_LIVELINESS_QOS:
230+
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC;
231+
break;
232+
default:
233+
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_UNKNOWN;
234+
break;
235+
}
236+
qos->liveliness_lease_duration.sec = dds_qos.qos.m_liveliness.lease_duration.seconds;
237+
qos->liveliness_lease_duration.nsec = dds_qos.qos.m_liveliness.lease_duration.nanosec;
238+
}
239+
240+
template
241+
void dds_qos_to_rmw_qos<eprosima::fastrtps::PublisherAttributes>(
242+
const eprosima::fastrtps::PublisherAttributes & dds_qos,
243+
rmw_qos_profile_t * qos);
244+
245+
template
246+
void dds_qos_to_rmw_qos<eprosima::fastrtps::SubscriberAttributes>(
247+
const eprosima::fastrtps::SubscriberAttributes & dds_qos,
248+
rmw_qos_profile_t * qos);

rmw_fastrtps_shared_cpp/src/rmw_publisher.cpp

Lines changed: 1 addition & 59 deletions
Original file line numberDiff line numberDiff line change
@@ -146,65 +146,7 @@ __rmw_publisher_get_actual_qos(
146146
const eprosima::fastrtps::PublisherAttributes & attributes =
147147
fastrtps_pub->getAttributes();
148148

149-
switch (attributes.topic.historyQos.kind) {
150-
case eprosima::fastrtps::KEEP_LAST_HISTORY_QOS:
151-
qos->history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
152-
break;
153-
case eprosima::fastrtps::KEEP_ALL_HISTORY_QOS:
154-
qos->history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
155-
break;
156-
default:
157-
qos->history = RMW_QOS_POLICY_HISTORY_UNKNOWN;
158-
break;
159-
}
160-
qos->depth = static_cast<size_t>(attributes.topic.historyQos.depth);
161-
162-
switch (attributes.qos.m_reliability.kind) {
163-
case eprosima::fastrtps::BEST_EFFORT_RELIABILITY_QOS:
164-
qos->reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
165-
break;
166-
case eprosima::fastrtps::RELIABLE_RELIABILITY_QOS:
167-
qos->reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
168-
break;
169-
default:
170-
qos->reliability = RMW_QOS_POLICY_RELIABILITY_UNKNOWN;
171-
break;
172-
}
173-
174-
switch (attributes.qos.m_durability.kind) {
175-
case eprosima::fastrtps::TRANSIENT_LOCAL_DURABILITY_QOS:
176-
qos->durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
177-
break;
178-
case eprosima::fastrtps::VOLATILE_DURABILITY_QOS:
179-
qos->durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
180-
break;
181-
default:
182-
qos->durability = RMW_QOS_POLICY_DURABILITY_UNKNOWN;
183-
break;
184-
}
185-
186-
qos->deadline.sec = attributes.qos.m_deadline.period.seconds;
187-
qos->deadline.nsec = attributes.qos.m_deadline.period.nanosec;
188-
189-
qos->lifespan.sec = attributes.qos.m_lifespan.duration.seconds;
190-
qos->lifespan.nsec = attributes.qos.m_lifespan.duration.nanosec;
191-
192-
switch (attributes.qos.m_liveliness.kind) {
193-
case eprosima::fastrtps::AUTOMATIC_LIVELINESS_QOS:
194-
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
195-
break;
196-
case eprosima::fastrtps::MANUAL_BY_PARTICIPANT_LIVELINESS_QOS:
197-
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE;
198-
break;
199-
case eprosima::fastrtps::MANUAL_BY_TOPIC_LIVELINESS_QOS:
200-
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC;
201-
break;
202-
default:
203-
qos->liveliness = RMW_QOS_POLICY_LIVELINESS_UNKNOWN;
204-
break;
205-
}
206-
qos->liveliness_lease_duration.sec = attributes.qos.m_liveliness.lease_duration.seconds;
207-
qos->liveliness_lease_duration.nsec = attributes.qos.m_liveliness.lease_duration.nanosec;
149+
dds_qos_to_rmw_qos(attributes, qos);
208150

209151
return RMW_RET_OK;
210152
}

rmw_fastrtps_shared_cpp/src/rmw_subscription.cpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -106,4 +106,27 @@ __rmw_subscription_count_matched_publishers(
106106
return RMW_RET_OK;
107107
}
108108

109+
rmw_ret_t
110+
__rmw_subscription_get_actual_qos(
111+
const rmw_subscription_t * subscription,
112+
rmw_qos_profile_t * qos)
113+
{
114+
RMW_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_INVALID_ARGUMENT);
115+
RMW_CHECK_ARGUMENT_FOR_NULL(qos, RMW_RET_INVALID_ARGUMENT);
116+
117+
auto info = static_cast<CustomSubscriberInfo *>(subscription->data);
118+
if (info == nullptr) {
119+
return RMW_RET_ERROR;
120+
}
121+
eprosima::fastrtps::Subscriber * fastrtps_sub = info->subscriber_;
122+
if (fastrtps_sub == nullptr) {
123+
return RMW_RET_ERROR;
124+
}
125+
const eprosima::fastrtps::SubscriberAttributes & attributes =
126+
fastrtps_sub->getAttributes();
127+
128+
dds_qos_to_rmw_qos(attributes, qos);
129+
130+
return RMW_RET_OK;
131+
}
109132
} // namespace rmw_fastrtps_shared_cpp

0 commit comments

Comments
 (0)