From e6acf762e6b0d008509b571e95240ccf97377ff3 Mon Sep 17 00:00:00 2001 From: CursedRock17 Date: Mon, 11 Mar 2024 14:31:22 -0400 Subject: [PATCH 1/4] Use templated Node Signed-off-by: CursedRock17 --- tf2_ros/include/tf2_ros/message_filter.h | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/tf2_ros/include/tf2_ros/message_filter.h b/tf2_ros/include/tf2_ros/message_filter.h index 06668185d..973cb4701 100644 --- a/tf2_ros/include/tf2_ros/message_filter.h +++ b/tf2_ros/include/tf2_ros/message_filter.h @@ -161,10 +161,11 @@ 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, + const NodeT & node, std::chrono::duration buffer_timeout = std::chrono::duration::max()) : MessageFilter( @@ -216,10 +217,11 @@ 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, + const NodeT & node, std::chrono::duration buffer_timeout = std::chrono::duration::max()) : MessageFilter( From f6d163ac1c54467d35e939121e600ff8ef205feb Mon Sep 17 00:00:00 2001 From: CursedRock17 Date: Thu, 14 Mar 2024 21:46:20 -0400 Subject: [PATCH 2/4] Using node_interfaces functions Signed-off-by: CursedRock17 --- tf2_ros/include/tf2_ros/message_filter.h | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/tf2_ros/include/tf2_ros/message_filter.h b/tf2_ros/include/tf2_ros/message_filter.h index 973cb4701..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" @@ -165,12 +167,13 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi typename TimeRepT = int64_t, typename TimeT = std::nano> MessageFilter( BufferT & buffer, const std::string & target_frame, uint32_t queue_size, - const NodeT & 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, @@ -221,12 +224,13 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi typename TimeRepT = int64_t, typename TimeT = std::nano> MessageFilter( F & f, BufferT & buffer, const std::string & target_frame, uint32_t queue_size, - const NodeT & 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) { } From 659b232301cefc453ef17c9956bdf946b2f960a1 Mon Sep 17 00:00:00 2001 From: CursedRock17 Date: Fri, 19 Apr 2024 00:48:10 -0400 Subject: [PATCH 3/4] Revert "Fix installation directory of .dll files in tf2_eigen_kdl (#657)" This reverts commit 3c509320fbed3b2962c24daee170d3b89d5d61e8. --- tf2_eigen_kdl/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tf2_eigen_kdl/CMakeLists.txt b/tf2_eigen_kdl/CMakeLists.txt index 6f5431d26..0b46c3cd1 100644 --- a/tf2_eigen_kdl/CMakeLists.txt +++ b/tf2_eigen_kdl/CMakeLists.txt @@ -46,7 +46,7 @@ install(TARGETS ${PROJECT_NAME} EXPORT export_${PROJECT_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib - RUNTIME DESTINATION bin) + RUNTIME DESTINATION lib) ament_export_dependencies( Eigen3 From 439aa6887e99223477f480ad086689cc91f4ef5f Mon Sep 17 00:00:00 2001 From: CursedRock17 Date: Fri, 19 Apr 2024 00:48:17 -0400 Subject: [PATCH 4/4] Revert "Revert "Fix installation directory of .dll files in tf2_eigen_kdl (#657)"" This reverts commit 0ed5d79cecd0e3bb10ef08a6471241b9d47ae315. --- tf2_eigen_kdl/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tf2_eigen_kdl/CMakeLists.txt b/tf2_eigen_kdl/CMakeLists.txt index 0b46c3cd1..6f5431d26 100644 --- a/tf2_eigen_kdl/CMakeLists.txt +++ b/tf2_eigen_kdl/CMakeLists.txt @@ -46,7 +46,7 @@ install(TARGETS ${PROJECT_NAME} EXPORT export_${PROJECT_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib - RUNTIME DESTINATION lib) + RUNTIME DESTINATION bin) ament_export_dependencies( Eigen3