Skip to content

Deprecated rmw_qos_profile_t in favour of rclcpp::QoS#364

Merged
ahcorde merged 4 commits intorollingfrom
ahcorde/rolling/rclcpp_qos
Jul 21, 2025
Merged

Deprecated rmw_qos_profile_t in favour of rclcpp::QoS#364
ahcorde merged 4 commits intorollingfrom
ahcorde/rolling/rclcpp_qos

Conversation

@ahcorde
Copy link
Collaborator

@ahcorde ahcorde commented Jun 25, 2025

Deprecated rmw_qos_profile_t in favour of rclcpp::QoS

Signed-off-by: Alejandro Hernandez Cordero <ahcorde@gmail.com>
@ahcorde ahcorde requested a review from mikeferguson June 25, 2025 11:40
@ahcorde ahcorde self-assigned this Jun 25, 2025
@ahcorde
Copy link
Collaborator Author

ahcorde commented Jun 27, 2025

@elsayedelsheikh you reviewed a similar PR in point_cloud_transport, do you mind to take a look here ?

@elsayedelsheikh
Copy link

@elsayedelsheikh you reviewed a similar PR in point_cloud_transport, do you mind to take a look here ?

Sure! I'll have a look :)

* \brief Subscribe to an image topic, version for class member function with shared_ptr.
*/
template<class T>
[[deprecated("Use subscribe(..., rclcpp::QoS, ...) instead")]]

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
[[deprecated("Use subscribe(..., rclcpp::QoS, ...) instead")]]

Copy link

@elsayedelsheikh elsayedelsheikh Jun 27, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Deprecate old method Line

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As well as old method on line

/*!
* \brief Subscribe to a camera, free function version.
*/
[[deprecated("Use create_publisher(..., rclcpp::QoS, ...) instead")]]

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
[[deprecated("Use create_publisher(..., rclcpp::QoS, ...) instead")]]
[[deprecated("Use create_camera_subscription(..., rclcpp::QoS, ...) instead")]]

/*!
* \brief Advertise a camera, free function version.
*/
[[deprecated("Use create_publisher(..., rclcpp::QoS, ...) instead")]]

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
[[deprecated("Use create_publisher(..., rclcpp::QoS, ...) instead")]]
[[deprecated("Use create_camera_publisher(..., rclcpp::QoS, ...) instead")]]

@elsayedelsheikh
Copy link

I noticed a default value is provided here which keeps the old API unchanged and custom_qos is optional ✅

rclcpp::QoS custom_qos = rclcpp::SystemDefaultsQoS(),

But this is not the case for other classes ❌ where new rclcpp::QoS is not optional anymore (similar to point_cloud_transport).

Which approach should be adapted? (Optional QoS✅ or not ❌)

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm confused here

Subscriber ImageTransport::subscribe(
const std::string & base_topic, uint32_t queue_size,
const Subscriber::Callback & callback,
const VoidPtr & tracked_object,
const TransportHints * transport_hints,
const rclcpp::SubscriptionOptions options)
{
(void) tracked_object;
rmw_qos_profile_t custom_qos = rmw_qos_profile_default;
custom_qos.depth = queue_size;
return create_subscription(
impl_->node_.get(), base_topic, callback,
getTransportOrDefault(transport_hints),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos),
options);
}
CameraPublisher ImageTransport::advertiseCamera(
const std::string & base_topic, uint32_t queue_size,
bool latch)
{
// TODO(ros2) implement when resolved: https://github.com/ros2/ros2/issues/464
(void) latch;
rmw_qos_profile_t custom_qos = rmw_qos_profile_default;
custom_qos.depth = queue_size;
return create_camera_publisher(impl_->node_.get(), base_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos));
}

In other methods, rclcpp::QoS was adapted from the beginning

  auto custom_qos = rclcpp::SystemDefaultsQoS();
  custom_qos.keep_last(queue_size);

Avoiding conversionrclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos)

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done ad5ee27

@ahcorde
Copy link
Collaborator Author

ahcorde commented Jul 7, 2025

I noticed a default value is provided here which keeps the old API unchanged and custom_qos is optional ✅

rclcpp::QoS custom_qos = rclcpp::SystemDefaultsQoS(),

But this is not the case for other classes ❌ where new rclcpp::QoS is not optional anymore (similar to point_cloud_transport).
Which approach should be adapted? (Optional QoS✅ or not ❌)

I have to remove the optional value because the signature of the methods will conflict.

ahcorde added 2 commits July 7, 2025 13:27
Signed-off-by: Alejandro Hernandez Cordero <ahcorde@gmail.com>
Signed-off-by: Alejandro Hernandez Cordero <ahcorde@gmail.com>
@ahcorde ahcorde requested a review from elsayedelsheikh July 14, 2025 14:53
Copy link

@elsayedelsheikh elsayedelsheikh left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM!

@ahcorde
Copy link
Collaborator Author

ahcorde commented Jul 18, 2025

Pulls: #364, ros2/rviz#1525
Gist: https://gist.githubusercontent.com/ahcorde/2524fd9a435413113c3e4ae24856259f/raw/0ce72171166d9eae7264336065b9fcd9c1001d2a/ros2.repos
BUILD args: --packages-above-and-dependencies image_transport
TEST args: --packages-above image_transport
ROS Distro: rolling
Job: ci_launcher
ci_launcher ran: https://ci.ros2.org/job/ci_launcher/16528

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Linux-rhel Build Status
  • Windows Build Status

@ahcorde
Copy link
Collaborator Author

ahcorde commented Jul 18, 2025

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Linux-rhel Build Status
  • Windows Build Status

@ahcorde ahcorde merged commit fbb8b0b into rolling Jul 21, 2025
2 checks passed
@ahcorde ahcorde deleted the ahcorde/rolling/rclcpp_qos branch July 21, 2025 11:45
nbbrooks added a commit to moveit/moveit2 that referenced this pull request Oct 12, 2025
* Fix image_common NodeT deprecation warnings from ros-perception/image_common#352 - migrate to NodeInterfaces

* Fix image_common rmw_qos_profile_t deprecation warnings from ros-perception/image_common#364 - migrate to rclcpp::QoS

* Fix rviz update float deprecation warnings from ros2/rviz#1533 - migrate to std::chrono::duration

* Fix geometry2 tf2_ros .h deprecation warnings from ros2/geometry2#805 - migrate Kilted and Rolling to .hpp

* Fix geometry2 tf2_ros NodeT deprecation warnings from ros2/geometry2#714 - migrate to NodeInterfaces

* Fix rclcpp spin_some deprecation warnings from ros2/rclcpp#2848 - migrate to SingleThreadedExecutor

---------

Co-authored-by: Andrea <realeandrea@yahoo.it>
helen9975 pushed a commit to personalrobotics/moveit2 that referenced this pull request Feb 17, 2026
* Fix image_common NodeT deprecation warnings from ros-perception/image_common#352 - migrate to NodeInterfaces

* Fix image_common rmw_qos_profile_t deprecation warnings from ros-perception/image_common#364 - migrate to rclcpp::QoS

* Fix rviz update float deprecation warnings from ros2/rviz#1533 - migrate to std::chrono::duration

* Fix geometry2 tf2_ros .h deprecation warnings from ros2/geometry2#805 - migrate Kilted and Rolling to .hpp

* Fix geometry2 tf2_ros NodeT deprecation warnings from ros2/geometry2#714 - migrate to NodeInterfaces

* Fix rclcpp spin_some deprecation warnings from ros2/rclcpp#2848 - migrate to SingleThreadedExecutor

---------

Co-authored-by: Andrea <realeandrea@yahoo.it>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants