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

MessageFilter Generalizated Nodes #661

Closed
wants to merge 4 commits into from
Closed
Changes from all commits
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
22 changes: 14 additions & 8 deletions tf2_ros/include/tf2_ros/message_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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<typename TimeRepT = int64_t, typename TimeT = std::nano>
template<typename NodeT = rclcpp::Node::SharedPtr,
typename TimeRepT = int64_t, typename TimeT = std::nano>
MessageFilter(
BufferT & buffer, const std::string & target_frame, uint32_t queue_size,
const rclcpp::Node::SharedPtr & node,
NodeT && node,
std::chrono::duration<TimeRepT, TimeT> buffer_timeout =
std::chrono::duration<TimeRepT, TimeT>::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<tf2::BufferCoreInterface, BufferT>::value,
Expand Down Expand Up @@ -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<class F, typename TimeRepT = int64_t, typename TimeT = std::nano>
template<class F, typename NodeT = rclcpp::Node::SharedPtr,
typename TimeRepT = int64_t, typename TimeT = std::nano>
MessageFilter(
F & f, BufferT & buffer, const std::string & target_frame, uint32_t queue_size,
const rclcpp::Node::SharedPtr & node,
NodeT && node,
std::chrono::duration<TimeRepT, TimeT> buffer_timeout =
std::chrono::duration<TimeRepT, TimeT>::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)
{
}

Expand Down