Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,8 @@ class RVIZ_COMMON_PUBLIC QosProfileProperty : public QObject
*/
void initialize(std::function<void(rclcpp::QoS)> qos_changed_callback);

void setBestEffort();

private Q_SLOTS:
void updateQosProfile();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,11 @@ void QosProfileProperty::initialize(std::function<void(rclcpp::QoS)> qos_changed
qos_changed_callback_ = std::move(qos_changed_callback);
}

void QosProfileProperty::setBestEffort()
{
reliability_policy_property_->setStdString("Best Effort");
}

void QosProfileProperty::updateQosProfile()
{
rmw_qos_profile_t profile = rmw_qos_profile_default;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,8 @@ void PointCloud2Display::onInitialize()
{
PC2RDClass::onInitialize();
point_cloud_common_->initialize(context_, scene_node_);

qos_profile_property_->setBestEffort();
}

void PointCloud2Display::processMessage(const sensor_msgs::msg::PointCloud2::ConstSharedPtr cloud)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,8 @@ void PointCloudDisplay::onInitialize()
{
MFDClass::onInitialize();
point_cloud_common_->initialize(context_, scene_node_);

qos_profile_property_->setBestEffort();
}

void PointCloudDisplay::processMessage(const sensor_msgs::msg::PointCloud::ConstSharedPtr cloud)
Expand Down