Skip to content

Commit 23725ab

Browse files
authored
Removed warnings in depth_image_proc (#1116)
Signed-off-by: Alejandro Hernandez Cordero <[email protected]>
1 parent ac8249e commit 23725ab

File tree

2 files changed

+2
-2
lines changed

2 files changed

+2
-2
lines changed

depth_image_proc/src/point_cloud_xyzi.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,7 @@ PointCloudXyziNode::PointCloudXyziNode(const rclcpp::NodeOptions & options)
102102
image_transport::getCameraInfoTopic(intensity_topic), false);
103103

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

depth_image_proc/src/point_cloud_xyzrgb_radial.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -112,7 +112,7 @@ PointCloudXyzrgbRadialNode::PointCloudXyzrgbRadialNode(const rclcpp::NodeOptions
112112
image_transport::getCameraInfoTopic(rgb_topic), false);
113113

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

0 commit comments

Comments
 (0)