Skip to content

Commit a76cf91

Browse files
authoredMar 6, 2024··
Select QoS reliability policy in DepthCloud Plugin (#1159)
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
1 parent 92023c9 commit a76cf91

File tree

2 files changed

+40
-2
lines changed

2 files changed

+40
-2
lines changed
 

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

+4
Original file line numberDiff line numberDiff line change
@@ -106,6 +106,8 @@ protected Q_SLOTS:
106106

107107
void transformerChangedCallback();
108108

109+
void updateQosProfile();
110+
109111
// Property callbacks
110112
virtual void updateTopic();
111113
virtual void updateTopicFilter();
@@ -160,6 +162,8 @@ protected Q_SLOTS:
160162
rclcpp::Time subscription_start_time_;
161163

162164
// RVIZ properties
165+
rviz_common::properties::EditableEnumProperty * reliability_policy_property_;
166+
rmw_qos_profile_t qos_profile_;
163167
rviz_common::properties::Property * topic_filter_property_;
164168
rviz_common::properties::IntProperty * queue_size_property_;
165169
rviz_common::properties::BoolProperty * use_auto_size_property_;

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

+36-2
Original file line numberDiff line numberDiff line change
@@ -84,6 +84,18 @@ DepthCloudDisplay::DepthCloudDisplay()
8484
QRegExp depth_filter("depth");
8585
depth_filter.setCaseSensitivity(Qt::CaseInsensitive);
8686

87+
reliability_policy_property_ = new rviz_common::properties::EditableEnumProperty(
88+
"Reliability Policy",
89+
"Best effort",
90+
"Set the reliability policy: When choosing 'Best effort', no guarantee will be given that the "
91+
"messages will be delivered, choosing 'Reliable', messages will be sent until received.", this,
92+
SLOT(updateQosProfile()));
93+
reliability_policy_property_->addOption("System Default");
94+
reliability_policy_property_->addOption("Reliable");
95+
reliability_policy_property_->addOption("Best effort");
96+
97+
qos_profile_ = rmw_qos_profile_sensor_data;
98+
8799
topic_filter_property_ =
88100
new rviz_common::properties::Property(
89101
"Topic Filter", true,
@@ -162,6 +174,26 @@ DepthCloudDisplay::DepthCloudDisplay()
162174
use_occlusion_compensation_property_, SLOT(updateOcclusionTimeOut()), this);
163175
}
164176

177+
void DepthCloudDisplay::updateQosProfile()
178+
{
179+
updateQueueSize();
180+
qos_profile_ = rmw_qos_profile_default;
181+
qos_profile_.depth = queue_size_;
182+
183+
auto policy = reliability_policy_property_->getString().toStdString();
184+
185+
if (policy == "Best effort") {
186+
qos_profile_.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
187+
188+
} else if (policy == "Reliable") {
189+
qos_profile_.reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
190+
} else {
191+
qos_profile_.reliability = RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT;
192+
}
193+
194+
updateTopic();
195+
}
196+
165197
void DepthCloudDisplay::transformerChangedCallback()
166198
{
167199
updateTopic();
@@ -225,6 +257,7 @@ void DepthCloudDisplay::updateQueueSize()
225257
depthmap_tf_filter_->setQueueSize(static_cast<uint32_t>(queue_size_property_->getInt()));
226258
}
227259
queue_size_ = queue_size_property_->getInt();
260+
qos_profile_.depth = queue_size_;
228261
}
229262

230263
void DepthCloudDisplay::updateUseAutoSize()
@@ -311,7 +344,8 @@ void DepthCloudDisplay::subscribe()
311344
depthmap_sub_->subscribe(
312345
rviz_ros_node_->get_raw_node().get(),
313346
depthmap_topic,
314-
depthmap_transport);
347+
depthmap_transport,
348+
qos_profile_);
315349

316350
depthmap_tf_filter_ =
317351
std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::Image,
@@ -353,7 +387,7 @@ void DepthCloudDisplay::subscribe()
353387
// subscribe to color image topic
354388
rgb_sub_->subscribe(
355389
rviz_ros_node_->get_raw_node().get(),
356-
color_topic, color_transport, rclcpp::SensorDataQoS().get_rmw_qos_profile());
390+
color_topic, color_transport, qos_profile_);
357391

358392
// connect message filters to synchronizer
359393
sync_depth_color_->connectInput(*depthmap_tf_filter_, *rgb_sub_);

0 commit comments

Comments
 (0)
Please sign in to comment.