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
2 changes: 1 addition & 1 deletion depth_image_proc/src/point_cloud_xyzi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ PointCloudXyziNode::PointCloudXyziNode(const rclcpp::NodeOptions & options)
image_transport::getCameraInfoTopic(intensity_topic), false);

// depth image can use different transport.(e.g. compressedDepth)
image_transport::TransportHints depth_hints(this, "raw", "depth_image_transport");
image_transport::TransportHints depth_hints(*this, "raw", "depth_image_transport");
sub_depth_.subscribe(*this, depth_topic, depth_hints.getTransport(),
rclcpp::SystemDefaultsQoS());

Expand Down
2 changes: 1 addition & 1 deletion depth_image_proc/src/point_cloud_xyzrgb_radial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ PointCloudXyzrgbRadialNode::PointCloudXyzrgbRadialNode(const rclcpp::NodeOptions
image_transport::getCameraInfoTopic(rgb_topic), false);

// depth image can use different transport.(e.g. compressedDepth)
image_transport::TransportHints depth_hints(this, "raw", "depth_image_transport");
image_transport::TransportHints depth_hints(*this, "raw", "depth_image_transport");
sub_depth_.subscribe(*this, depth_topic, depth_hints.getTransport(),
rclcpp::SystemDefaultsQoS());

Expand Down
Loading