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

Removed deprecation warnings #1010

Merged
merged 7 commits into from
Jul 23, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
3 changes: 2 additions & 1 deletion depth_image_proc/src/disparity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,8 @@ 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(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)));
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
}
};
pub_disparity_ = create_publisher<stereo_msgs::msg::DisparityImage>(
Expand Down
3 changes: 2 additions & 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,8 @@ 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(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)));
}
};
pub_point_cloud_ = create_publisher<PointCloud>("points", rclcpp::SensorDataQoS(), pub_options);
Expand Down
3 changes: 2 additions & 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,8 @@ 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(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)));
}
};
pub_point_cloud_ = create_publisher<sensor_msgs::msg::PointCloud2>(
Expand Down
6 changes: 4 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,10 @@ 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(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)));
}
};
pub_point_cloud_ = create_publisher<PointCloud2>("points", rclcpp::SensorDataQoS(), pub_options);
Expand Down
3 changes: 2 additions & 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,8 @@ 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(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)));
}
};
pub_point_cloud_ = create_publisher<PointCloud2>("points", rclcpp::SensorDataQoS(), pub_options);
Expand Down
6 changes: 4 additions & 2 deletions depth_image_proc/src/register.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,8 +139,10 @@ 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(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)));
sub_rgb_info_.subscribe(this, "rgb/camera_info",
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)));
}
};
// For compressed topics to remap appropriately, we need to pass a
Expand Down
6 changes: 2 additions & 4 deletions image_view/include/image_view/disparity_view_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,8 @@ class DisparityViewNode
{
public:
explicit DisparityViewNode(const rclcpp::NodeOptions & options);
explicit DisparityViewNode(const DisparityViewNode &) = default;
explicit DisparityViewNode(DisparityViewNode &&) = default;
DisparityViewNode & operator=(const DisparityViewNode &) = default;
DisparityViewNode & operator=(DisparityViewNode &&) = default;
explicit DisparityViewNode(const DisparityViewNode &) = delete;
explicit DisparityViewNode(DisparityViewNode &&) = delete;
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
~DisparityViewNode();

private:
Expand Down
8 changes: 4 additions & 4 deletions image_view/include/image_view/image_view_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,10 +48,10 @@ class ImageViewNode
{
public:
explicit ImageViewNode(const rclcpp::NodeOptions & options);
explicit ImageViewNode(const ImageViewNode &) = default;
explicit ImageViewNode(ImageViewNode &&) = default;
ImageViewNode & operator=(const ImageViewNode &) = default;
ImageViewNode & operator=(ImageViewNode &&) = default;
explicit ImageViewNode(const ImageViewNode &) = delete;
explicit ImageViewNode(ImageViewNode &&) = delete;
ImageViewNode & operator=(const ImageViewNode &) = delete;
ImageViewNode & operator=(ImageViewNode &&) = delete;
~ImageViewNode();

private:
Expand Down
8 changes: 4 additions & 4 deletions image_view/include/image_view/stereo_view_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,10 +77,10 @@ class StereoViewNode
{
public:
explicit StereoViewNode(const rclcpp::NodeOptions & options);
explicit StereoViewNode(const StereoViewNode &) = default;
explicit StereoViewNode(StereoViewNode &&) = default;
StereoViewNode & operator=(const StereoViewNode &) = default;
StereoViewNode & operator=(StereoViewNode &&) = default;
explicit StereoViewNode(const StereoViewNode &) = delete;
explicit StereoViewNode(StereoViewNode &&) = delete;
StereoViewNode & operator=(const StereoViewNode &) = delete;
StereoViewNode & operator=(StereoViewNode &&) = delete;
~StereoViewNode();

private:
Expand Down
8 changes: 4 additions & 4 deletions image_view/include/image_view/video_recorder_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,10 @@ class VideoRecorderNode
{
public:
explicit VideoRecorderNode(const rclcpp::NodeOptions & options);
explicit VideoRecorderNode(const VideoRecorderNode &) = default;
explicit VideoRecorderNode(VideoRecorderNode &&) = default;
VideoRecorderNode & operator=(const VideoRecorderNode &) = default;
VideoRecorderNode & operator=(VideoRecorderNode &&) = default;
explicit VideoRecorderNode(const VideoRecorderNode &) = delete;
explicit VideoRecorderNode(VideoRecorderNode &&) = delete;
VideoRecorderNode & operator=(const VideoRecorderNode &) = delete;
VideoRecorderNode & operator=(VideoRecorderNode &&) = delete;
~VideoRecorderNode();

private:
Expand Down
3 changes: 2 additions & 1 deletion image_view/src/stereo_view_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,8 @@ 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(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)));

RCLCPP_INFO(
this->get_logger(),
Expand Down
6 changes: 4 additions & 2 deletions stereo_image_proc/src/stereo_image_proc/disparity_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -326,10 +326,12 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)

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_l_info_.subscribe(this, left_info_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts);
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
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);
sub_r_info_.subscribe(this, right_info_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts);
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
}
};

Expand Down
9 changes: 6 additions & 3 deletions stereo_image_proc/src/stereo_image_proc/point_cloud_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -191,9 +191,12 @@ PointCloudNode::PointCloudNode(const rclcpp::NodeOptions & options)

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);
sub_l_info_.subscribe(this, left_info_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts);
sub_r_info_.subscribe(this, right_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts);
sub_disparity_.subscribe(this, disparity_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts);
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
}
};
pub_points2_ = create_publisher<sensor_msgs::msg::PointCloud2>("points2", 1, pub_opts);
Expand Down
Loading