Skip to content

Commit 17b57c3

Browse files
authored
Replace rmw_qos_profile_t with rclcpp::QoS (#1525)
Signed-off-by: Alejandro Hernandez Cordero <[email protected]>
1 parent 9b2a208 commit 17b57c3

File tree

3 files changed

+9
-10
lines changed

3 files changed

+9
-10
lines changed

rviz_default_plugins/include/rviz_default_plugins/displays/depth_cloud/depth_cloud_display.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -165,7 +165,7 @@ protected Q_SLOTS:
165165

166166
// RVIZ properties
167167
rviz_common::properties::EditableEnumProperty * reliability_policy_property_;
168-
rmw_qos_profile_t qos_profile_;
168+
rclcpp::QoS qos_profile_;
169169
rviz_common::properties::Property * topic_filter_property_;
170170
rviz_common::properties::IntProperty * queue_size_property_;
171171
rviz_common::properties::BoolProperty * use_auto_size_property_;

rviz_default_plugins/include/rviz_default_plugins/displays/image/image_transport_display.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -118,7 +118,7 @@ class ImageTransportDisplay : public rviz_common::_RosTopicDisplay
118118
node.get(),
119119
getBaseTopicFromTopic(topic_property_->getTopicStd()),
120120
getTransportFromTopic(topic_property_->getTopicStd()),
121-
qos_profile.get_rmw_qos_profile());
121+
qos_profile);
122122
subscription_start_time_ = node->now();
123123
subscription_callback_ = subscription_->registerCallback(
124124
std::bind(

rviz_default_plugins/src/rviz_default_plugins/displays/depth_cloud/depth_cloud_display.cpp

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,7 @@ DepthCloudDisplay::DepthCloudDisplay()
7676
, depthmap_tf_filter_(nullptr)
7777
, rgb_sub_()
7878
, cam_info_sub_()
79+
, qos_profile_(rclcpp::SensorDataQoS())
7980
, queue_size_(5)
8081
, angular_thres_(0.5f)
8182
, trans_thres_(0.01f)
@@ -95,8 +96,6 @@ DepthCloudDisplay::DepthCloudDisplay()
9596
reliability_policy_property_->addOption("Reliable");
9697
reliability_policy_property_->addOption("Best effort");
9798

98-
qos_profile_ = rmw_qos_profile_sensor_data;
99-
10099
topic_filter_property_ =
101100
new rviz_common::properties::Property(
102101
"Topic Filter", true,
@@ -178,18 +177,18 @@ DepthCloudDisplay::DepthCloudDisplay()
178177
void DepthCloudDisplay::updateQosProfile()
179178
{
180179
updateQueueSize();
181-
qos_profile_ = rmw_qos_profile_default;
182-
qos_profile_.depth = queue_size_;
180+
qos_profile_ = rclcpp::SystemDefaultsQoS();
181+
qos_profile_.keep_last(queue_size_);
183182

184183
auto policy = reliability_policy_property_->getString().toStdString();
185184

186185
if (policy == "Best effort") {
187-
qos_profile_.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
186+
qos_profile_.best_effort();
188187

189188
} else if (policy == "Reliable") {
190-
qos_profile_.reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
189+
qos_profile_.reliable();
191190
} else {
192-
qos_profile_.reliability = RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT;
191+
qos_profile_.reliability_best_available();
193192
}
194193

195194
updateTopic();
@@ -258,7 +257,7 @@ void DepthCloudDisplay::updateQueueSize()
258257
depthmap_tf_filter_->setQueueSize(static_cast<uint32_t>(queue_size_property_->getInt()));
259258
}
260259
queue_size_ = queue_size_property_->getInt();
261-
qos_profile_.depth = queue_size_;
260+
qos_profile_.keep_last(queue_size_);
262261
}
263262

264263
void DepthCloudDisplay::updateUseAutoSize()

0 commit comments

Comments
 (0)