Skip to content

Commit

Permalink
Removed deprecation warnings (#1010)
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 Jul 23, 2024
1 parent 54b74c0 commit 54fff5d
Show file tree
Hide file tree
Showing 9 changed files with 25 additions and 19 deletions.
2 changes: 1 addition & 1 deletion depth_image_proc/src/disparity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)
std::string topic = node_base->resolve_topic_or_service_name("left/image_rect", false);
image_transport::TransportHints hints(this);
sub_depth_image_.subscribe(this, topic, hints.getTransport());
sub_info_.subscribe(this, "right/camera_info");
sub_info_.subscribe(this, "right/camera_info", rclcpp::QoS(10));
}
};
pub_disparity_ = create_publisher<stereo_msgs::msg::DisparityImage>(
Expand Down
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 @@ -108,7 +108,7 @@ PointCloudXyziNode::PointCloudXyziNode(const rclcpp::NodeOptions & options)
// intensity uses normal ros transport hints.
image_transport::TransportHints hints(this, "raw");
sub_intensity_.subscribe(this, intensity_topic, hints.getTransport());
sub_info_.subscribe(this, intensity_info_topic);
sub_info_.subscribe(this, intensity_info_topic, rclcpp::QoS(10));
}
};
pub_point_cloud_ = create_publisher<PointCloud>("points", rclcpp::SensorDataQoS(), pub_options);
Expand Down
2 changes: 1 addition & 1 deletion depth_image_proc/src/point_cloud_xyzi_radial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ PointCloudXyziRadialNode::PointCloudXyziRadialNode(const rclcpp::NodeOptions & o
// intensity uses normal ros transport hints.
image_transport::TransportHints hints(this);
sub_intensity_.subscribe(this, intensity_topic, hints.getTransport());
sub_info_.subscribe(this, intensity_info_topic);
sub_info_.subscribe(this, intensity_info_topic, rclcpp::QoS(10));
}
};
pub_point_cloud_ = create_publisher<sensor_msgs::msg::PointCloud2>(
Expand Down
5 changes: 3 additions & 2 deletions depth_image_proc/src/point_cloud_xyzrgb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,8 +133,9 @@ PointCloudXyzrgbNode::PointCloudXyzrgbNode(const rclcpp::NodeOptions & options)
image_transport::TransportHints hints(this);
sub_rgb_.subscribe(
this, rgb_topic,
hints.getTransport(), rmw_qos_profile_default, sub_opts);
sub_info_.subscribe(this, rgb_info_topic);
hints.getTransport(),
rmw_qos_profile_default, sub_opts);
sub_info_.subscribe(this, rgb_info_topic, rclcpp::QoS(10));
}
};
pub_point_cloud_ = create_publisher<PointCloud2>("points", rclcpp::SensorDataQoS(), pub_options);
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 @@ -118,7 +118,7 @@ PointCloudXyzrgbRadialNode::PointCloudXyzrgbRadialNode(const rclcpp::NodeOptions
// rgb uses normal ros transport hints.
image_transport::TransportHints hints(this, "raw");
sub_rgb_.subscribe(this, rgb_topic, hints.getTransport());
sub_info_.subscribe(this, rgb_info_topic);
sub_info_.subscribe(this, rgb_info_topic, rclcpp::QoS(10));
}
};
pub_point_cloud_ = create_publisher<PointCloud2>("points", rclcpp::SensorDataQoS(), pub_options);
Expand Down
4 changes: 2 additions & 2 deletions depth_image_proc/src/register.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,8 +139,8 @@ RegisterNode::RegisterNode(const rclcpp::NodeOptions & options)
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");
sub_rgb_info_.subscribe(this, "rgb/camera_info");
sub_depth_info_.subscribe(this, "depth/camera_info", rclcpp::QoS(10));
sub_rgb_info_.subscribe(this, "rgb/camera_info", rclcpp::QoS(10));
}
};
// For compressed topics to remap appropriately, we need to pass a
Expand Down
2 changes: 1 addition & 1 deletion image_view/src/stereo_view_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ StereoViewNode::StereoViewNode(const rclcpp::NodeOptions & options)
// Subscribe to three input topics.
left_sub_.subscribe(this, left_topic, hints.getTransport());
right_sub_.subscribe(this, right_topic, hints.getTransport());
disparity_sub_.subscribe(this, disparity_topic);
disparity_sub_.subscribe(this, disparity_topic, rclcpp::QoS(10));

RCLCPP_INFO(
this->get_logger(),
Expand Down
12 changes: 7 additions & 5 deletions stereo_image_proc/src/stereo_image_proc/disparity_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -315,7 +315,7 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)
image_transport::getCameraInfoTopic(right_topic), false);

// REP-2003 specifies that subscriber should be SensorDataQoS
const auto sensor_data_qos = rclcpp::SensorDataQoS().get_rmw_qos_profile();
const auto sensor_data_qos = rclcpp::SensorDataQoS();

// Support image transport for compression
image_transport::TransportHints hints(this);
Expand All @@ -325,11 +325,13 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)
sub_opts.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();

sub_l_image_.subscribe(
this, left_topic, hints.getTransport(), sensor_data_qos, sub_opts);
sub_l_info_.subscribe(this, left_info_topic, sensor_data_qos, sub_opts);
this, left_topic, hints.getTransport(), sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sub_l_info_.subscribe(this, left_info_topic,
sensor_data_qos, sub_opts);
sub_r_image_.subscribe(
this, right_topic, hints.getTransport(), sensor_data_qos, sub_opts);
sub_r_info_.subscribe(this, right_info_topic, sensor_data_qos, sub_opts);
this, right_topic, hints.getTransport(), sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sub_r_info_.subscribe(this, right_info_topic,
sensor_data_qos, sub_opts);
}
};

Expand Down
13 changes: 8 additions & 5 deletions stereo_image_proc/src/stereo_image_proc/point_cloud_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ PointCloudNode::PointCloudNode(const rclcpp::NodeOptions & options)
image_transport::getCameraInfoTopic(left_topic), false);

// REP-2003 specifies that subscriber should be SensorDataQoS
const auto sensor_data_qos = rclcpp::SensorDataQoS().get_rmw_qos_profile();
const auto sensor_data_qos = rclcpp::SensorDataQoS();

// Support image transport for compression
image_transport::TransportHints hints(this);
Expand All @@ -190,10 +190,13 @@ PointCloudNode::PointCloudNode(const rclcpp::NodeOptions & options)
sub_opts.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();

sub_l_image_.subscribe(
this, left_topic, hints.getTransport(), sensor_data_qos, sub_opts);
sub_l_info_.subscribe(this, left_info_topic, sensor_data_qos, sub_opts);
sub_r_info_.subscribe(this, right_topic, sensor_data_qos, sub_opts);
sub_disparity_.subscribe(this, disparity_topic, sensor_data_qos, sub_opts);
this, left_topic, hints.getTransport(), sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sub_l_info_.subscribe(this, left_info_topic,
sensor_data_qos, sub_opts);
sub_r_info_.subscribe(this, right_topic,
sensor_data_qos, sub_opts);
sub_disparity_.subscribe(this, disparity_topic,
sensor_data_qos, sub_opts);
}
};
pub_points2_ = create_publisher<sensor_msgs::msg::PointCloud2>("points2", 1, pub_opts);
Expand Down

0 comments on commit 54fff5d

Please sign in to comment.