diff --git a/tf2_ros/include/tf2_ros/message_filter.h b/tf2_ros/include/tf2_ros/message_filter.h index 06668185d..2d587705b 100644 --- a/tf2_ros/include/tf2_ros/message_filter.h +++ b/tf2_ros/include/tf2_ros/message_filter.h @@ -50,6 +50,8 @@ #include "message_filters/connection.h" #include "message_filters/message_traits.h" #include "message_filters/simple_filter.h" +#include "rclcpp/node_interfaces/get_node_logging_interface.hpp" +#include "rclcpp/node_interfaces/get_node_clock_interface.hpp" #include "tf2/buffer_core_interface.h" #include "tf2/time.h" #include "tf2_ros/async_buffer_interface.h" @@ -161,15 +163,17 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi * \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 + template MessageFilter( BufferT & buffer, const std::string & target_frame, uint32_t queue_size, - const rclcpp::Node::SharedPtr & node, + NodeT && node, std::chrono::duration buffer_timeout = std::chrono::duration::max()) : MessageFilter( - buffer, target_frame, queue_size, node->get_node_logging_interface(), - node->get_node_clock_interface(), buffer_timeout) + buffer, target_frame, queue_size, + rclcpp::node_interfaces::get_node_logging_interface(node), + rclcpp::node_interfaces::get_node_clock_interface(node), buffer_timeout) { static_assert( std::is_base_of::value, @@ -216,15 +220,17 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi * \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 + template MessageFilter( F & f, BufferT & buffer, const std::string & target_frame, uint32_t queue_size, - const rclcpp::Node::SharedPtr & node, + NodeT && node, std::chrono::duration buffer_timeout = std::chrono::duration::max()) : MessageFilter( - f, buffer, target_frame, queue_size, node->get_node_logging_interface(), - node->get_node_clock_interface(), buffer_timeout) + f, buffer, target_frame, queue_size, + rclcpp::node_interfaces::get_node_logging_interface(node), + rclcpp::node_interfaces::get_node_clock_interface(node), buffer_timeout) { }