Skip to content

Commit

Permalink
Depth image transport configure susbcribers (#844) (#845)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Jan 17, 2024
1 parent fcd3939 commit 8076d4e
Showing 1 changed file with 17 additions and 2 deletions.
19 changes: 17 additions & 2 deletions depth_image_proc/src/point_cloud_xyzrgb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,12 +109,27 @@ void PointCloudXyzrgbNode::connectCb()
std::string depth_image_transport_param = "depth_image_transport";
image_transport::TransportHints depth_hints(this, "raw", depth_image_transport_param);

rclcpp::SubscriptionOptions sub_opts;
// Update the subscription options to allow reconfigurable qos settings.
sub_opts.qos_overriding_options = rclcpp::QosOverridingOptions {
{
// Here all policies that are desired to be reconfigurable are listed.
rclcpp::QosPolicyKind::Depth,
rclcpp::QosPolicyKind::Durability,
rclcpp::QosPolicyKind::History,
rclcpp::QosPolicyKind::Reliability,
}};

// depth image can use different transport.(e.g. compressedDepth)
sub_depth_.subscribe(this, "depth_registered/image_rect", depth_hints.getTransport());
sub_depth_.subscribe(
this, "depth_registered/image_rect",
depth_hints.getTransport(), rmw_qos_profile_default, sub_opts);

// rgb uses normal ros transport hints.
image_transport::TransportHints hints(this, "raw");
sub_rgb_.subscribe(this, "rgb/image_rect_color", hints.getTransport());
sub_rgb_.subscribe(
this, "rgb/image_rect_color",
hints.getTransport(), rmw_qos_profile_default, sub_opts);
sub_info_.subscribe(this, "rgb/camera_info");
}
}
Expand Down

0 comments on commit 8076d4e

Please sign in to comment.