Deprecated rmw_qos_profile_t in favour of rclcpp::QoS#364
Conversation
Signed-off-by: Alejandro Hernandez Cordero <ahcorde@gmail.com>
|
@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")]] |
There was a problem hiding this comment.
| [[deprecated("Use subscribe(..., rclcpp::QoS, ...) instead")]] |
There was a problem hiding this comment.
Deprecate old method Line
There was a problem hiding this comment.
As well as old method on line
| /*! | ||
| * \brief Subscribe to a camera, free function version. | ||
| */ | ||
| [[deprecated("Use create_publisher(..., rclcpp::QoS, ...) instead")]] |
There was a problem hiding this comment.
| [[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")]] |
There was a problem hiding this comment.
| [[deprecated("Use create_publisher(..., rclcpp::QoS, ...) instead")]] | |
| [[deprecated("Use create_camera_publisher(..., rclcpp::QoS, ...) instead")]] |
|
I noticed a default value is provided here which keeps the old API unchanged and 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 ❌) |
There was a problem hiding this comment.
I'm confused here
image_common/image_transport/src/image_transport.cpp
Lines 240 to 268 in daf6e7b
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)
I have to remove the optional value because the signature of the methods will conflict. |
Signed-off-by: Alejandro Hernandez Cordero <ahcorde@gmail.com>
image_transport/include/image_transport/simple_publisher_plugin.hpp
Outdated
Show resolved
Hide resolved
image_transport/include/image_transport/simple_subscriber_plugin.hpp
Outdated
Show resolved
Hide resolved
Signed-off-by: Alejandro Hernandez Cordero <ahcorde@gmail.com>
|
Pulls: #364, ros2/rviz#1525 |
* 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>
* 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>
Deprecated
rmw_qos_profile_tin favour ofrclcpp::QoS