File tree Expand file tree Collapse file tree 4 files changed +14
-7
lines changed Expand file tree Collapse file tree 4 files changed +14
-7
lines changed Original file line number Diff line number Diff line change 2929
3030#include " rclcpp/macros.hpp"
3131#include " rclcpp/mapped_ring_buffer.hpp"
32+ #include " rclcpp/qos.hpp"
3233#include " rclcpp/qos_event.hpp"
3334#include " rclcpp/type_support_decl.hpp"
3435#include " rclcpp/visibility_control.hpp"
@@ -153,10 +154,11 @@ class PublisherBase : public std::enable_shared_from_this<PublisherBase>
153154 * If the underlying setting in use can't be represented in ROS terms,
154155 * it will be set to RMW_QOS_POLICY_*_UNKNOWN.
155156 * May throw runtime_error when an unexpected error occurs.
157+ *
156158 * \return The actual qos settings.
157159 */
158160 RCLCPP_PUBLIC
159- rmw_qos_profile_t
161+ rclcpp::QoS
160162 get_actual_qos () const ;
161163
162164 // / Compare this publisher to a gid.
Original file line number Diff line number Diff line change 2727
2828#include " rclcpp/any_subscription_callback.hpp"
2929#include " rclcpp/macros.hpp"
30+ #include " rclcpp/qos.hpp"
3031#include " rclcpp/qos_event.hpp"
3132#include " rclcpp/type_support_decl.hpp"
3233#include " rclcpp/visibility_control.hpp"
@@ -106,10 +107,11 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
106107 * If the underlying setting in use can't be represented in ROS terms,
107108 * it will be set to RMW_QOS_POLICY_*_UNKNOWN.
108109 * May throw runtime_error when an unexpected error occurs.
110+ *
109111 * \return The actual qos settings.
110112 */
111113 RCLCPP_PUBLIC
112- rmw_qos_profile_t
114+ rclcpp::QoS
113115 get_actual_qos () const ;
114116
115117 // / Borrow a new message.
Original file line number Diff line number Diff line change @@ -205,7 +205,7 @@ PublisherBase::get_intra_process_subscription_count() const
205205 return ipm->get_subscription_count (intra_process_publisher_id_);
206206}
207207
208- rmw_qos_profile_t
208+ rclcpp::QoS
209209PublisherBase::get_actual_qos () const
210210{
211211 const rmw_qos_profile_t * qos = rcl_publisher_get_actual_qos (&publisher_handle_);
@@ -214,7 +214,8 @@ PublisherBase::get_actual_qos() const
214214 rcl_reset_error ();
215215 throw std::runtime_error (msg);
216216 }
217- return *qos;
217+
218+ return rclcpp::QoS (rclcpp::QoSInitialization::from_rmw (*qos), *qos);
218219}
219220
220221bool
@@ -264,7 +265,8 @@ PublisherBase::setup_intra_process(
264265 const rcl_publisher_options_t & intra_process_options)
265266{
266267 // Intraprocess configuration is not allowed with "durability" qos policy non "volatile".
267- if (this ->get_actual_qos ().durability != RMW_QOS_POLICY_DURABILITY_VOLATILE) {
268+ auto actual_durability = this ->get_actual_qos ().get_rmw_qos_profile ().durability ;
269+ if (actual_durability != RMW_QOS_POLICY_DURABILITY_VOLATILE) {
268270 throw std::invalid_argument (
269271 " intraprocess communication is not allowed with durability qos policy non-volatile" );
270272 }
Original file line number Diff line number Diff line change @@ -129,7 +129,7 @@ SubscriptionBase::get_event_handlers() const
129129 return event_handlers_;
130130}
131131
132- rmw_qos_profile_t
132+ rclcpp::QoS
133133SubscriptionBase::get_actual_qos () const
134134{
135135 const rmw_qos_profile_t * qos = rcl_subscription_get_actual_qos (subscription_handle_.get ());
@@ -138,7 +138,8 @@ SubscriptionBase::get_actual_qos() const
138138 rcl_reset_error ();
139139 throw std::runtime_error (msg);
140140 }
141- return *qos;
141+
142+ return rclcpp::QoS (rclcpp::QoSInitialization::from_rmw (*qos), *qos);
142143}
143144
144145const rosidl_message_type_support_t &
You can’t perform that action at this time.
0 commit comments