diff --git a/tf2_ros/include/tf2_ros/buffer.hpp b/tf2_ros/include/tf2_ros/buffer.hpp index aabfd06bf..958e3c99f 100644 --- a/tf2_ros/include/tf2_ros/buffer.hpp +++ b/tf2_ros/include/tf2_ros/buffer.hpp @@ -95,24 +95,6 @@ class Buffer : public BufferInterface, public AsyncBufferInterface, public tf2:: RequiredInterfaces node_interfaces = RequiredInterfaces(), const rclcpp::QoS & qos = rclcpp::ServicesQoS()); - /** \brief Constructor for a Buffer object - * \param clock A clock to use for time and sleeping - * \param cache_time How long to keep a history of transforms - * \param node If passed advertise the view_frames service that exposes debugging information from the buffer - * \param qos If passed change the quality of service of the frames_server_ service - */ - template, - std::enable_if_t::value, bool> = true> - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of NoteT")]] - Buffer( - rclcpp::Clock::SharedPtr clock, - tf2::Duration cache_time = tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME), - NodeT && node = NodeT(), - const rclcpp::QoS & qos = rclcpp::ServicesQoS()) - : Buffer(clock, cache_time, *node, qos) - { - } - /** \brief Get the transform between two frames by frame ID. * \param target_frame The frame to which data should be transformed * \param source_frame The frame where the data originated diff --git a/tf2_ros/include/tf2_ros/create_timer_ros.hpp b/tf2_ros/include/tf2_ros/create_timer_ros.hpp index 353533917..be3a175c0 100644 --- a/tf2_ros/include/tf2_ros/create_timer_ros.hpp +++ b/tf2_ros/include/tf2_ros/create_timer_ros.hpp @@ -63,13 +63,6 @@ class CreateTimerROS : public CreateTimerInterface RequiredInterfaces node_interfaces, rclcpp::CallbackGroup::SharedPtr callback_group = nullptr); - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]] - TF2_ROS_PUBLIC - CreateTimerROS( - NodeBaseInterface::SharedPtr node_base, - NodeTimersInterface::SharedPtr node_timers, - rclcpp::CallbackGroup::SharedPtr callback_group = nullptr); - virtual ~CreateTimerROS() = default; /** diff --git a/tf2_ros/include/tf2_ros/message_filter.hpp b/tf2_ros/include/tf2_ros/message_filter.hpp index 7053d0334..97e1aea97 100644 --- a/tf2_ros/include/tf2_ros/message_filter.hpp +++ b/tf2_ros/include/tf2_ros/message_filter.hpp @@ -220,102 +220,6 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi connectInput(f); } - /** - * \brief Constructor - * - * \param buffer The buffer this filter should use - * \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. - * \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). - * \param node The ros2 node to use for logging and clock operations - * \param buffer_timeout The timeout duration after requesting transforms from the buffer. - */ - template - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of Node::SharedPtr&")]] - MessageFilter( - BufferT & buffer, const std::string & target_frame, uint32_t queue_size, - const rclcpp::Node::SharedPtr & node, - std::chrono::duration buffer_timeout = - std::chrono::duration::max()) - : MessageFilter( - buffer, target_frame, queue_size, - RequiredInterfaces(node->get_node_logging_interface(), node->get_node_clock_interface()), - buffer_timeout) - { - } - - /** - * \brief Constructor - * - * \param buffer The buffer this filter should use - * \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. - * \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). - * \param node_logging The logging interface to use for any log messages - * \param node_clock The clock interface to use to get the node clock - * \param buffer_timeout The timeout duration after requesting transforms from the buffer. - */ - template - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]] - MessageFilter( - BufferT & buffer, const std::string & target_frame, uint32_t queue_size, - const NodeLoggingInterface::SharedPtr & node_logging, - const NodeClockInterface::SharedPtr & node_clock, - std::chrono::duration buffer_timeout = - std::chrono::duration::max()) - : MessageFilter( - buffer, target_frame, queue_size, - RequiredInterfaces(node_logging, node_clock), buffer_timeout) - { - } - - /** - * \brief Constructor - * - * \param f The filter to connect this filter's input to. Often will be a message_filters::Subscriber. - * \param buffer The buffer this filter should use - * \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. - * \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). - * \param node The ros2 node to use for logging and clock operations - * \param buffer_timeout The timeout duration after requesting transforms from the buffer. - */ - template - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of Node::SharedPtr&")]] - MessageFilter( - F & f, BufferT & buffer, const std::string & target_frame, uint32_t queue_size, - const rclcpp::Node::SharedPtr & node, - std::chrono::duration buffer_timeout = - std::chrono::duration::max()) - : MessageFilter( - f, buffer, target_frame, queue_size, - RequiredInterfaces(node->get_node_logging_interface(), node->get_node_clock_interface()), - buffer_timeout) - { - } - - /** - * \brief Constructor - * - * \param f The filter to connect this filter's input to. Often will be a message_filters::Subscriber. - * \param buffer The buffer this filter should use - * \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. - * \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). - * \param node_logging The logging interface to use for any log messages - * \param node_clock The clock interface to use to get the node clock - * \param buffer_timeout The timeout duration after requesting transforms from the buffer. - */ - template - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]] - MessageFilter( - F & f, BufferT & buffer, const std::string & target_frame, uint32_t queue_size, - const NodeLoggingInterface::SharedPtr & node_logging, - const NodeClockInterface::SharedPtr & node_clock, - std::chrono::duration buffer_timeout = - std::chrono::duration::max()) - : MessageFilter( - f, buffer, target_frame, queue_size, - RequiredInterfaces(node_logging, node_clock), buffer_timeout) - { - } - /** * \brief Connect this filter's input to another filter's output. If this filter is already connected, disconnects first. */ diff --git a/tf2_ros/include/tf2_ros/static_transform_broadcaster.hpp b/tf2_ros/include/tf2_ros/static_transform_broadcaster.hpp index 558db5376..f6b9bfd19 100644 --- a/tf2_ros/include/tf2_ros/static_transform_broadcaster.hpp +++ b/tf2_ros/include/tf2_ros/static_transform_broadcaster.hpp @@ -36,7 +36,6 @@ #define TF2_ROS__STATIC_TRANSFORM_BROADCASTER_HPP_ #include -#include #include #include "tf2_ros/visibility_control.hpp" @@ -45,7 +44,6 @@ #include "rclcpp/node_interfaces/get_node_parameters_interface.hpp" #include "rclcpp/node_interfaces/get_node_topics_interface.hpp" #include "rclcpp/rclcpp.hpp" -#include "rcpputils/pointer_traits.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" #include "tf2_msgs/msg/tf_message.hpp" #include "tf2_ros/qos.hpp" @@ -85,47 +83,6 @@ class StaticTransformBroadcaster node_parameters, node_topics, "/tf_static", qos, options); } - /** \brief Node constructor */ - template, - std::enable_if_t::value, bool> = true> - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of NodeT")]] - StaticTransformBroadcaster( - NodeT && node, - const rclcpp::QoS & qos = StaticBroadcasterQoS(), - const rclcpp::PublisherOptionsWithAllocator & options = [] () { - rclcpp::PublisherOptionsWithAllocator options; - options.qos_overriding_options = rclcpp::QosOverridingOptions{ - rclcpp::QosPolicyKind::Depth, - rclcpp::QosPolicyKind::History, - rclcpp::QosPolicyKind::Reliability}; - return options; - } ()) - : StaticTransformBroadcaster( - RequiredInterfaces(node->get_node_parameters_interface(), - node->get_node_topics_interface()), qos, options) - { - } - - /** \brief Node interfaces constructor */ - template> - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]] - StaticTransformBroadcaster( - NodeParametersInterface::SharedPtr node_parameters, - NodeTopicsInterface::SharedPtr node_topics, - const rclcpp::QoS & qos = StaticBroadcasterQoS(), - const rclcpp::PublisherOptionsWithAllocator & options = [] () { - rclcpp::PublisherOptionsWithAllocator options; - options.qos_overriding_options = rclcpp::QosOverridingOptions{ - rclcpp::QosPolicyKind::Depth, - rclcpp::QosPolicyKind::History, - rclcpp::QosPolicyKind::Reliability}; - return options; - } ()) - : StaticTransformBroadcaster( - RequiredInterfaces(node_parameters, node_topics), qos, options) - { - } - /** \brief Send a TransformStamped message * The stamped data structure includes frame_id, and time, and parent_id already. */ TF2_ROS_PUBLIC diff --git a/tf2_ros/include/tf2_ros/transform_broadcaster.hpp b/tf2_ros/include/tf2_ros/transform_broadcaster.hpp index 9c7411b92..179213fb9 100644 --- a/tf2_ros/include/tf2_ros/transform_broadcaster.hpp +++ b/tf2_ros/include/tf2_ros/transform_broadcaster.hpp @@ -36,7 +36,6 @@ #define TF2_ROS__TRANSFORM_BROADCASTER_HPP_ #include -#include #include #include "tf2_ros/visibility_control.hpp" @@ -45,7 +44,6 @@ #include "rclcpp/node_interfaces/get_node_parameters_interface.hpp" #include "rclcpp/node_interfaces/get_node_topics_interface.hpp" #include "rclcpp/rclcpp.hpp" -#include "rcpputils/pointer_traits.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" #include "tf2_msgs/msg/tf_message.hpp" #include "tf2_ros/qos.hpp" @@ -87,48 +85,6 @@ class TransformBroadcaster node_parameters, node_topics, "/tf", qos, options); } - /** \brief Node constructor */ - template, - std::enable_if_t::value, bool> = true> - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of NodeT")]] - TransformBroadcaster( - NodeT && node, - const rclcpp::QoS & qos = DynamicBroadcasterQoS(), - const rclcpp::PublisherOptionsWithAllocator & options = [] () { - rclcpp::PublisherOptionsWithAllocator options; - options.qos_overriding_options = rclcpp::QosOverridingOptions{ - rclcpp::QosPolicyKind::Depth, - rclcpp::QosPolicyKind::Durability, - rclcpp::QosPolicyKind::History, - rclcpp::QosPolicyKind::Reliability}; - return options; - } ()) - : TransformBroadcaster( - RequiredInterfaces(node->get_node_parameters_interface(), - node->get_node_topics_interface()), qos, options) - { - } - - /** \brief Node interfaces constructor */ - template> - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]] - TransformBroadcaster( - NodeParametersInterface::SharedPtr node_parameters, - NodeTopicsInterface::SharedPtr node_topics, - const rclcpp::QoS & qos = DynamicBroadcasterQoS(), - const rclcpp::PublisherOptionsWithAllocator & options = [] () { - rclcpp::PublisherOptionsWithAllocator options; - options.qos_overriding_options = rclcpp::QosOverridingOptions{ - rclcpp::QosPolicyKind::Depth, - rclcpp::QosPolicyKind::Durability, - rclcpp::QosPolicyKind::History, - rclcpp::QosPolicyKind::Reliability}; - return options; - } ()) - : TransformBroadcaster(RequiredInterfaces(node_parameters, node_topics), qos, options) - { - } - /** \brief Send a TransformStamped message * * The transform ʰTₐ added is from `child_frame_id`, `a` to `header.frame_id`, diff --git a/tf2_ros/include/tf2_ros/transform_listener.hpp b/tf2_ros/include/tf2_ros/transform_listener.hpp index 28854856c..2d741e211 100644 --- a/tf2_ros/include/tf2_ros/transform_listener.hpp +++ b/tf2_ros/include/tf2_ros/transform_listener.hpp @@ -36,7 +36,6 @@ #include #include -#include #include #include @@ -46,7 +45,6 @@ #include "tf2_msgs/msg/tf_message.hpp" #include "rclcpp/rclcpp.hpp" -#include "rcpputils/pointer_traits.hpp" #include "rclcpp/node_interfaces/node_interfaces.hpp" #include "rclcpp/node_interfaces/get_node_base_interface.hpp" #include "rclcpp/node_interfaces/get_node_logging_interface.hpp" @@ -135,63 +133,6 @@ class TransformListener static_only); } - /** \brief Node constructor */ - template, - std::enable_if_t::value, bool> = true> - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of NodeT")]] - TransformListener( - tf2::BufferCore & buffer, - NodeT && node, - bool spin_thread = true, - const rclcpp::QoS & qos = DynamicListenerQoS(), - const rclcpp::QoS & static_qos = StaticListenerQoS(), - const rclcpp::SubscriptionOptionsWithAllocator & options = - detail::get_default_transform_listener_sub_options(), - const rclcpp::SubscriptionOptionsWithAllocator & static_options = - detail::get_default_transform_listener_static_sub_options(), - bool static_only = false) - : TransformListener( - buffer, - RequiredInterfaces(node->get_node_base_interface(), node->get_node_logging_interface(), - node->get_node_parameters_interface(), node->get_node_topics_interface()), - spin_thread, - qos, - static_qos, - options, - static_options, - static_only) - { - } - - /** \brief Node interface constructor */ - template> - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]] - TransformListener( - tf2::BufferCore & buffer, - NodeBaseInterface::SharedPtr node_base, - NodeLoggingInterface::SharedPtr node_logging, - NodeParametersInterface::SharedPtr node_parameters, - NodeTopicsInterface::SharedPtr node_topics, - bool spin_thread = true, - const rclcpp::QoS & qos = DynamicListenerQoS(), - const rclcpp::QoS & static_qos = StaticListenerQoS(), - const rclcpp::SubscriptionOptionsWithAllocator & options = - detail::get_default_transform_listener_sub_options(), - const rclcpp::SubscriptionOptionsWithAllocator & static_options = - detail::get_default_transform_listener_static_sub_options(), - bool static_only = false) - : TransformListener( - buffer, - RequiredInterfaces(node_base, node_logging, node_parameters, node_topics), - spin_thread, - qos, - static_qos, - options, - static_options, - static_only) - { - } - TF2_ROS_PUBLIC virtual ~TransformListener(); @@ -328,55 +269,6 @@ class StaticTransformListener : public TransformListener { } - /** \brief Node constructor */ - template, - std::enable_if_t::value, bool> = true> - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of NodeT")]] - StaticTransformListener( - tf2::BufferCore & buffer, - NodeT && node, - bool spin_thread = true, - const rclcpp::QoS & static_qos = StaticListenerQoS(), - const rclcpp::SubscriptionOptionsWithAllocator & static_options = - detail::get_default_transform_listener_static_sub_options()) - : TransformListener( - buffer, - RequiredInterfaces(node->get_node_base_interface(), node->get_node_logging_interface(), - node->get_node_parameters_interface(), node->get_node_topics_interface()), - spin_thread, - rclcpp::QoS(1), - static_qos, - rclcpp::SubscriptionOptionsWithAllocator(), - static_options, - true) - { - } - - /** \brief Node interface constructor */ - template> - [[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]] - StaticTransformListener( - tf2::BufferCore & buffer, - NodeBaseInterface::SharedPtr node_base, - NodeLoggingInterface::SharedPtr node_logging, - NodeParametersInterface::SharedPtr node_parameters, - NodeTopicsInterface::SharedPtr node_topics, - bool spin_thread = true, - const rclcpp::QoS & static_qos = StaticListenerQoS(), - const rclcpp::SubscriptionOptionsWithAllocator & static_options = - detail::get_default_transform_listener_static_sub_options()) - : TransformListener( - buffer, - RequiredInterfaces(node_base, node_logging, node_parameters, node_topics), - spin_thread, - rclcpp::QoS(1), - static_qos, - rclcpp::SubscriptionOptionsWithAllocator(), - static_options, - true) - { - } - TF2_ROS_PUBLIC virtual ~StaticTransformListener() { diff --git a/tf2_ros/src/create_timer_ros.cpp b/tf2_ros/src/create_timer_ros.cpp index 6f24f02fd..36258387d 100644 --- a/tf2_ros/src/create_timer_ros.cpp +++ b/tf2_ros/src/create_timer_ros.cpp @@ -51,16 +51,6 @@ CreateTimerROS::CreateTimerROS( { } -CreateTimerROS::CreateTimerROS( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, - rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers, - rclcpp::CallbackGroup::SharedPtr callback_group) -: CreateTimerROS(rclcpp::node_interfaces::NodeInterfaces< - rclcpp::node_interfaces::NodeBaseInterface, - rclcpp::node_interfaces::NodeTimersInterface>(node_base, node_timers), callback_group) -{ -} - TimerHandle CreateTimerROS::createTimer( rclcpp::Clock::SharedPtr clock, diff --git a/tf2_ros/test/listener_unittest.cpp b/tf2_ros/test/listener_unittest.cpp index c077df717..cdb8d5c2c 100644 --- a/tf2_ros/test/listener_unittest.cpp +++ b/tf2_ros/test/listener_unittest.cpp @@ -40,68 +40,6 @@ #include "rclcpp/rclcpp.hpp" #include "builtin_interfaces/msg/time.hpp" -TEST(tf2_ros_test_listener, transform_listener_deprecated) -{ - auto node = rclcpp::Node::make_shared("tf2_ros_test_listener_transform_listener"); - - rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_SYSTEM_TIME); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - tf2_ros::Buffer buffer(clock); - tf2_ros::TransformListener tfl(buffer, node, false); - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif - - rclcpp::executors::SingleThreadedExecutor executor; - executor.add_node(node); - // Start spinning in a thread - std::thread spin_thread = std::thread([&executor] () { - executor.spin(); - }); - - geometry_msgs::msg::TransformStamped ts; - ts.transform.rotation.w = 1; - ts.header.frame_id = "a"; - ts.header.stamp = rclcpp::Time(10, 0); - ts.child_frame_id = "b"; - ts.transform.translation.x = 1; - ts.transform.translation.y = 2; - ts.transform.translation.z = 3; - - buffer.setTransform(ts, "authority"); - - std::this_thread::sleep_for(std::chrono::milliseconds(200)); - - EXPECT_TRUE(buffer.canTransform("a", "b", tf2::timeFromSec(0))); - - geometry_msgs::msg::TransformStamped out_rootc = buffer.lookupTransform( - "a", "b", - rclcpp::Time()); - - EXPECT_EQ(1, out_rootc.transform.translation.x); - EXPECT_EQ(2, out_rootc.transform.translation.y); - EXPECT_EQ(3, out_rootc.transform.translation.z); - EXPECT_EQ(1, out_rootc.transform.rotation.w); - EXPECT_EQ(0, out_rootc.transform.rotation.x); - EXPECT_EQ(0, out_rootc.transform.rotation.y); - EXPECT_EQ(0, out_rootc.transform.rotation.z); - - executor.cancel(); - spin_thread.join(); - node.reset(); -} - TEST(tf2_ros_test_listener, transform_listener) { auto node = rclcpp::Node::make_shared("tf2_ros_test_listener_transform_listener"); diff --git a/tf2_ros/test/message_filter_test.cpp b/tf2_ros/test/message_filter_test.cpp index d110971d5..edf17c882 100644 --- a/tf2_ros/test/message_filter_test.cpp +++ b/tf2_ros/test/message_filter_test.cpp @@ -56,78 +56,6 @@ void filter_callback(const geometry_msgs::msg::PointStamped & msg) filter_callback_fired++; } -TEST(tf2_ros_message_filter, construction_and_destruction_deprecated) -{ - auto node = rclcpp::Node::make_shared("test_message_filter_node"); - rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_SYSTEM_TIME); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - tf2_ros::Buffer buffer(clock); - - // Node constructor with defaults - { - tf2_ros::MessageFilter filter(buffer, "map", 10, node); - } - - // Node constructor no defaults - { - tf2_ros::MessageFilter filter( - buffer, "map", 10, node, std::chrono::milliseconds(100)); - } - - // Node interface constructor with defaults - { - tf2_ros::MessageFilter filter( - buffer, "map", 10, node->get_node_logging_interface(), node->get_node_clock_interface()); - } - - // Node interface constructor no defaults - { - tf2_ros::MessageFilter filter( - buffer, "map", 10, node->get_node_logging_interface(), node->get_node_clock_interface(), - std::chrono::seconds(42)); - } - - message_filters::Subscriber sub; - // Filter + node constructor with defaults - { - tf2_ros::MessageFilter filter(sub, buffer, "map", 10, node); - } - - // Filter + node constructor no defaults - { - tf2_ros::MessageFilter filter( - sub, buffer, "map", 10, node, std::chrono::hours(1)); - } - - // Filter + node interface constructor with defaults - { - tf2_ros::MessageFilter filter( - sub, buffer, "map", 10, node->get_node_logging_interface(), - node->get_node_clock_interface()); - } - - // Filter + node interface constructor no defaults - { - tf2_ros::MessageFilter filter( - sub, buffer, "map", 10, node->get_node_logging_interface(), node->get_node_clock_interface(), - std::chrono::microseconds(0)); - } - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif -} - TEST(tf2_ros_message_filter, construction_and_destruction) { auto node = rclcpp::Node::make_shared("test_message_filter_node"); @@ -196,36 +124,6 @@ TEST(tf2_ros_message_filter, construction_and_destruction) } } -TEST(tf2_ros_message_filter, get_target_frames_deprecated) -{ - auto node = rclcpp::Node::make_shared("test_message_filter_node"); - rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_SYSTEM_TIME); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - tf2_ros::Buffer buffer(clock); - tf2_ros::MessageFilter filter(buffer, "map", 10, node); - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif - ASSERT_STREQ(filter.getTargetFramesString().c_str(), "map"); - - std::vector frames; - frames.push_back("odom"); - frames.push_back("map"); - filter.setTargetFrames(frames); - ASSERT_STREQ(filter.getTargetFramesString().c_str(), "odom, map"); -} - TEST(tf2_ros_message_filter, get_target_frames) { auto node = rclcpp::Node::make_shared("test_message_filter_node"); @@ -242,109 +140,6 @@ TEST(tf2_ros_message_filter, get_target_frames) ASSERT_STREQ(filter.getTargetFramesString().c_str(), "odom, map"); } -TEST(tf2_ros_message_filter, multiple_frames_and_time_tolerance_deprecated) -{ - const ::testing::TestInfo * const test_info = - ::testing::UnitTest::GetInstance()->current_test_info(); - std::string node_name = "tf2_ros_message_filter_" + std::string(test_info->name()); - for (char & c : node_name) { - if (!isalnum(c)) { - c = '_'; - } - } - auto node = rclcpp::Node::make_shared(node_name); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - auto create_timer_interface = std::make_shared( - node->get_node_base_interface(), - node->get_node_timers_interface()); - - rclcpp::QoS default_qos = - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); - message_filters::Subscriber sub; - sub.subscribe(node, "point", default_qos); - - rclcpp::Clock::SharedPtr clock = node->get_clock(); - tf2_ros::Buffer buffer(clock); - buffer.setCreateTimerInterface(create_timer_interface); - tf2_ros::TransformListener tfl(buffer); - tf2_ros::MessageFilter filter(buffer, "map", 10, node); - filter.connectInput(sub); - filter.registerCallback(&filter_callback); - - // Register multiple target frames - std::vector frames; - frames.push_back("odom"); - frames.push_back("map"); - filter.setTargetFrames(frames); - // Set a non-zero time tolerance - filter.setTolerance(rclcpp::Duration(1, 0)); - - // Publish static transforms so the frame transformations will always be valid - tf2_ros::StaticTransformBroadcaster tfb(node); - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif - - geometry_msgs::msg::TransformStamped map_to_odom; - map_to_odom.header.stamp = rclcpp::Time(0, 0, clock->get_clock_type()); - map_to_odom.header.frame_id = "map"; - map_to_odom.child_frame_id = "odom"; - map_to_odom.transform.rotation.w = 1.0; - tfb.sendTransform(map_to_odom); - - geometry_msgs::msg::TransformStamped odom_to_base; - odom_to_base.header.stamp = rclcpp::Time(0, 0, clock->get_clock_type()); - odom_to_base.header.frame_id = "odom"; - odom_to_base.child_frame_id = "base"; - odom_to_base.transform.rotation.w = 1.0; - tfb.sendTransform(odom_to_base); - - rclcpp::executors::SingleThreadedExecutor executor; - executor.add_node(node); - - // Wait for transforms to be available - auto start_wait = clock->now(); - while (rclcpp::ok() && - !buffer.canTransform("map", "base", tf2::TimePointZero) && - (clock->now() - start_wait) < rclcpp::Duration(5, 0)) - { - executor.spin_some(); - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - } - - rclcpp::Publisher::SharedPtr pub; - pub = node->create_publisher("point", 10); - geometry_msgs::msg::PointStamped point; - point.header.stamp = clock->now(); - point.header.frame_id = "base"; - point.point.x = 0.1; - - int count = 0; - while (rclcpp::ok() && ++count < 60) { - pub->publish(point); - for (int i = 0; i < 10; ++i) { - executor.spin_some(); - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - } - if (filter_callback_fired.load() > 5) { - break; - } - } - - ASSERT_GT(filter_callback_fired, 0); -} - TEST(tf2_ros_message_filter, multiple_frames_and_time_tolerance) { const ::testing::TestInfo * const test_info = diff --git a/tf2_ros/test/test_static_transform_broadcaster.cpp b/tf2_ros/test/test_static_transform_broadcaster.cpp index 3d79f39c1..36b1ae98d 100644 --- a/tf2_ros/test/test_static_transform_broadcaster.cpp +++ b/tf2_ros/test/test_static_transform_broadcaster.cpp @@ -67,36 +67,6 @@ class CustomComposableNode : public rclcpp::Node std::shared_ptr tf_broadcaster_; }; -TEST(tf2_test_static_transform_broadcaster, transform_broadcaster_rclcpp_node_deprecated) -{ - auto node = rclcpp::Node::make_shared("tf2_ros_message_filter"); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - // Construct static tf broadcaster from node pointer - { - tf2_ros::StaticTransformBroadcaster tfb(node); - } - // Construct static tf broadcaster from node interfaces - { - tf2_ros::StaticTransformBroadcaster tfb( - node->get_node_parameters_interface(), - node->get_node_topics_interface()); - } - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif -} - TEST(tf2_test_static_transform_broadcaster, transform_broadcaster_rclcpp_node) { auto node = rclcpp::Node::make_shared("tf2_ros_message_filter"); @@ -125,36 +95,6 @@ TEST(tf2_test_static_transform_broadcaster, transform_broadcaster_with_intraproc custom_node->init_tf_broadcaster(); } -TEST(tf2_test_static_transform_broadcaster, transform_broadcaster_custom_rclcpp_node_deprecated) -{ - auto node = std::make_shared("tf2_ros_message_filter"); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - // Construct static tf broadcaster from node pointer - { - tf2_ros::StaticTransformBroadcaster tfb(node); - } - // Construct static tf broadcaster from node interfaces - { - tf2_ros::StaticTransformBroadcaster tfb( - node->get_node_parameters_interface(), - node->get_node_topics_interface()); - } - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif -} - TEST(tf2_test_static_transform_broadcaster, transform_broadcaster_custom_rclcpp_node) { auto node = std::make_shared("tf2_ros_message_filter"); diff --git a/tf2_ros/test/test_transform_broadcaster.cpp b/tf2_ros/test/test_transform_broadcaster.cpp index 26867bac4..e70f242ca 100644 --- a/tf2_ros/test/test_transform_broadcaster.cpp +++ b/tf2_ros/test/test_transform_broadcaster.cpp @@ -51,36 +51,6 @@ class CustomNode : public rclcpp::Node std::shared_ptr tf_broadcaster_; }; -TEST(tf2_test_transform_broadcaster, transform_broadcaster_rclcpp_node_deprecated) -{ - auto node = rclcpp::Node::make_shared("tf2_ros_message_filter"); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - // Construct tf broadcaster from node pointer - { - tf2_ros::TransformBroadcaster tfb(node); - } - // Construct tf broadcaster from node interfaces - { - tf2_ros::TransformBroadcaster tfb( - node->get_node_parameters_interface(), - node->get_node_topics_interface()); - } - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif -} - TEST(tf2_test_transform_broadcaster, transform_broadcaster_rclcpp_node) { auto node = rclcpp::Node::make_shared("tf2_ros_message_filter"); @@ -99,36 +69,6 @@ TEST(tf2_test_transform_broadcaster, transform_broadcaster_rclcpp_node) } } -TEST(tf2_test_transform_broadcaster, transform_broadcaster_custom_rclcpp_node_deprecated) -{ - auto node = std::make_shared("tf2_ros_message_filter"); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - // Construct tf broadcaster from node pointer - { - tf2_ros::TransformBroadcaster tfb(node); - } - // Construct tf broadcaster from node interfaces - { - tf2_ros::TransformBroadcaster tfb( - node->get_node_parameters_interface(), - node->get_node_topics_interface()); - } - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif -} - TEST(tf2_test_transform_broadcaster, transform_broadcaster_custom_rclcpp_node) { auto node = std::make_shared("tf2_ros_message_filter"); diff --git a/tf2_ros/test/test_transform_listener.cpp b/tf2_ros/test/test_transform_listener.cpp index 004278826..4077e9217 100644 --- a/tf2_ros/test/test_transform_listener.cpp +++ b/tf2_ros/test/test_transform_listener.cpp @@ -92,30 +92,6 @@ class CustomComposableNode : public rclcpp::Node std::shared_ptr tf_listener_; }; -TEST(tf2_test_transform_listener, transform_listener_rclcpp_node_deprecated) -{ - auto node = rclcpp::Node::make_shared("tf2_ros_message_filter"); - - rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_SYSTEM_TIME); - tf2_ros::Buffer buffer(clock); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - tf2_ros::TransformListener tfl(buffer, node, false); - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif -} - TEST(tf2_test_transform_listener, transform_listener_rclcpp_node) { auto node = rclcpp::Node::make_shared("tf2_ros_message_filter"); @@ -125,30 +101,6 @@ TEST(tf2_test_transform_listener, transform_listener_rclcpp_node) tf2_ros::TransformListener tfl(buffer, *node, false); } -TEST(tf2_test_transform_listener, transform_listener_custom_rclcpp_node_deprecated) -{ - auto node = std::make_shared("tf2_ros_message_filter"); - - rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_SYSTEM_TIME); - tf2_ros::Buffer buffer(clock); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - tf2_ros::TransformListener tfl(buffer, node, false); - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif -} - TEST(tf2_test_transform_listener, transform_listener_custom_rclcpp_node) { auto node = std::make_shared("tf2_ros_message_filter"); @@ -181,30 +133,6 @@ TEST(tf2_test_static_transform_listener, static_transform_listener_rclcpp_node) tf2_ros::Buffer buffer(clock); } -TEST(tf2_test_static_transform_listener, static_transform_listener_custom_rclcpp_node_deprecated) -{ - auto node = std::make_shared("tf2_ros_static_transform_listener"); - - rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_SYSTEM_TIME); - tf2_ros::Buffer buffer(clock); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - tf2_ros::StaticTransformListener tfl(buffer, node, false); - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif -} - TEST(tf2_test_static_transform_listener, static_transform_listener_custom_rclcpp_node) { auto node = std::make_shared("tf2_ros_static_transform_listener"); @@ -229,67 +157,6 @@ TEST(tf2_test_static_transform_listener, static_transform_listener_with_intrapro custom_node->init_static_tf_listener(); } -TEST(tf2_test_listeners, static_vs_dynamic_deprecated) -{ - auto node = rclcpp::Node::make_shared("tf2_ros_static_transform_listener"); - rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_SYSTEM_TIME); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - tf2_ros::Buffer dynamic_buffer(clock); - tf2_ros::Buffer static_buffer(clock); - tf2_ros::TransformListener tfl(dynamic_buffer, node, true); - tf2_ros::StaticTransformListener stfl(static_buffer, node, true); - tf2_ros::TransformBroadcaster broadcaster(node); - tf2_ros::StaticTransformBroadcaster static_broadcaster(node); - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif - - geometry_msgs::msg::TransformStamped static_trans; - static_trans.header.stamp = clock->now(); - static_trans.header.frame_id = "parent_static"; - static_trans.child_frame_id = "child_static"; - static_trans.transform.rotation.w = 1.0; - static_broadcaster.sendTransform(static_trans); - - geometry_msgs::msg::TransformStamped dynamic_trans; - dynamic_trans.header.frame_id = "parent_dynamic"; - dynamic_trans.child_frame_id = "child_dynamic"; - dynamic_trans.transform.rotation.w = 1.0; - - rclcpp::executors::SingleThreadedExecutor executor; - executor.add_node(node); - - for (int i = 0; i < 10; ++i) { - dynamic_trans.header.stamp = clock->now(); - broadcaster.sendTransform(dynamic_trans); - - executor.spin_some(); - rclcpp::sleep_for(std::chrono::milliseconds(10)); - } - - // Dynamic buffer should have both dynamic and static transforms available - EXPECT_NO_THROW( - dynamic_buffer.lookupTransform("parent_dynamic", "child_dynamic", tf2::TimePointZero)); - EXPECT_NO_THROW(dynamic_buffer.lookupTransform("parent_static", "child_static", clock->now())); - - // Static buffer should have only static transforms available - EXPECT_THROW( - static_buffer.lookupTransform("parent_dynamic", "child_dynamic", tf2::TimePointZero), - tf2::LookupException); - EXPECT_NO_THROW(static_buffer.lookupTransform("parent_static", "child_static", clock->now())); -} - TEST(tf2_test_listeners, static_vs_dynamic) { auto node = rclcpp::Node::make_shared("tf2_ros_static_transform_listener"); diff --git a/tf2_ros/test/time_reset_test.cpp b/tf2_ros/test/time_reset_test.cpp index 3b6036627..145ce632c 100644 --- a/tf2_ros/test/time_reset_test.cpp +++ b/tf2_ros/test/time_reset_test.cpp @@ -52,85 +52,6 @@ void spin_for_a_second(std::shared_ptr & node) } } -TEST(tf2_ros_time_reset_test, time_backwards_deprecated) -{ - std::shared_ptr node_ = std::make_shared( - "transform_listener_backwards_reset"); - rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_SYSTEM_TIME); - - #ifdef _MSC_VER - #pragma warning(push) - #pragma warning(disable : 4996) - #else - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #endif - - tf2_ros::Buffer buffer(clock); - tf2_ros::TransformListener tfl(buffer, node_); - tf2_ros::TransformBroadcaster tfb(node_); - - #ifdef _MSC_VER - #pragma warning(pop) - #else - #pragma GCC diagnostic pop - #endif - - auto clock_pub = node_->create_publisher("/clock", 1); - - // basic test - ASSERT_FALSE(buffer.canTransform("foo", "bar", rclcpp::Time(101, 0))); - - // make sure endpoints have discovered each other - spin_for_a_second(node_); - - rosgraph_msgs::msg::Clock c; - c.clock = rclcpp::Time(100, 0); - clock_pub->publish(c); - - // set the transform - geometry_msgs::msg::TransformStamped msg; - msg.header.stamp = rclcpp::Time(100, 0); - msg.header.frame_id = "foo"; - msg.child_frame_id = "bar"; - msg.transform.rotation.w = 0.0; - msg.transform.rotation.x = 1.0; - msg.transform.rotation.y = 0.0; - msg.transform.rotation.z = 0.0; - tfb.sendTransform(msg); - msg.header.stamp = rclcpp::Time(102, 0); - tfb.sendTransform(msg); - - // make sure it arrives - spin_for_a_second(node_); - - // verify it's been set - ASSERT_TRUE(buffer.canTransform("foo", "bar", rclcpp::Time(101, 0))); - - // TODO(ahcorde): review this - // c.clock.sec = 90; - // c.clock.nanosec = 0; - // clock_pub->publish(c); - // - // // make sure it arrives - // rclcpp::spin_some(node_); - // sleep(1); - // - // //Send anoterh message to trigger clock test on an unrelated frame - // msg.header.stamp.sec = 110; - // msg.header.stamp.nanosec = 0; - // msg.header.frame_id = "foo2"; - // msg.child_frame_id = "bar2"; - // tfb.sendTransform(msg); - // - // // make sure it arrives - // rclcpp::spin_some(node_); - // sleep(1); - // - // //verify the data's been cleared - // ASSERT_FALSE(buffer.canTransform("foo", "bar", tf2::timeFromSec(101))); -} - TEST(tf2_ros_time_reset_test, time_backwards) { std::shared_ptr node_ = std::make_shared(