Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Support QoS override parameters in depth_image_proc/register #1043

Merged
merged 2 commits into from
Nov 25, 2024
Merged
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
11 changes: 8 additions & 3 deletions depth_image_proc/src/register.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,14 +133,19 @@ RegisterNode::RegisterNode(const rclcpp::NodeOptions & options)
sub_depth_info_.unsubscribe();
sub_rgb_info_.unsubscribe();
} else if (!sub_depth_image_.getSubscriber()) {
// Allow overriding QoS settings (history, depth, reliability)
rclcpp::SubscriptionOptions sub_options;
sub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();

// For compressed topics to remap appropriately, we need to pass a
// fully expanded and remapped topic name to image_transport
auto node_base = this->get_node_base_interface();
std::string topic = node_base->resolve_topic_or_service_name("depth/image_rect", false);
image_transport::TransportHints hints(this, "raw", "depth_image_transport");
sub_depth_image_.subscribe(this, topic, hints.getTransport());
sub_depth_info_.subscribe(this, "depth/camera_info", rclcpp::QoS(10));
sub_rgb_info_.subscribe(this, "rgb/camera_info", rclcpp::QoS(10));
sub_depth_image_.subscribe(this, topic, hints.getTransport(), rmw_qos_profile_default,
sub_options);
sub_depth_info_.subscribe(this, "depth/camera_info", rclcpp::QoS(10), sub_options);
sub_rgb_info_.subscribe(this, "rgb/camera_info", rclcpp::QoS(10), sub_options);
}
};
// For compressed topics to remap appropriately, we need to pass a
Expand Down