From be4629d6e5018c1791c85c583f5846fca6ea7336 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Mon, 23 Feb 2026 21:08:13 -0500 Subject: [PATCH 01/23] initial port to ros2 Signed-off-by: solonovamax --- CMakeLists.txt | 231 ++++++++++-------- include/sensor_filters/FilterChainBase.h | 108 ++++---- include/sensor_filters/FilterChainNode.h | 25 +- include/sensor_filters/FilterChainNodelet.h | 58 ----- include/sensor_filters/ImageFilterChainBase.h | 17 +- .../PointCloud2FilterChainBase.h | 23 +- nodelets.xml | 95 ------- src/CompressedImageFilterChainNode.cc | 7 +- src/CompressedImageFilterChainNodelet.cc | 9 - src/ImageFilterChainBase.cc | 27 +- src/ImageFilterChainNode.cc | 7 +- src/ImageFilterChainNodelet.cc | 10 - src/ImuFilterChainNode.cc | 7 +- src/ImuFilterChainNodelet.cc | 9 - src/JoyFilterChainNode.cc | 7 +- src/JoyFilterChainNodelet.cc | 9 - src/LaserScanFilterChainNode.cc | 7 +- src/LaserScanFilterChainNodelet.cc | 9 - src/MagneticFieldFilterChainNode.cc | 7 +- src/MagneticFieldFilterChainNodelet.cc | 9 - src/MultiEchoLaserScanFilterChainNode.cc | 7 +- src/MultiEchoLaserScanFilterChainNodelet.cc | 9 - src/NavSatFixFilterChainNode.cc | 7 +- src/NavSatFixFilterChainNodelet.cc | 9 - src/PointCloud2FilterChainBase.cc | 27 +- src/PointCloud2FilterChainNode.cc | 7 +- src/PointCloud2FilterChainNodelet.cc | 10 - src/PointCloudFilterChainNode.cc | 7 +- src/PointCloudFilterChainNodelet.cc | 9 - src/RangeFilterChainNode.cc | 7 +- src/RangeFilterChainNodelet.cc | 9 - src/RelativeHumidityFilterChainNode.cc | 7 +- src/RelativeHumidityFilterChainNodelet.cc | 9 - src/TemperatureFilterChainNode.cc | 7 +- src/TemperatureFilterChainNodelet.cc | 9 - 35 files changed, 269 insertions(+), 552 deletions(-) delete mode 100644 include/sensor_filters/FilterChainNodelet.h delete mode 100644 nodelets.xml delete mode 100644 src/CompressedImageFilterChainNodelet.cc delete mode 100644 src/ImageFilterChainNodelet.cc delete mode 100644 src/ImuFilterChainNodelet.cc delete mode 100644 src/JoyFilterChainNodelet.cc delete mode 100644 src/LaserScanFilterChainNodelet.cc delete mode 100644 src/MagneticFieldFilterChainNodelet.cc delete mode 100644 src/MultiEchoLaserScanFilterChainNodelet.cc delete mode 100644 src/NavSatFixFilterChainNodelet.cc delete mode 100644 src/PointCloud2FilterChainNodelet.cc delete mode 100644 src/PointCloudFilterChainNodelet.cc delete mode 100644 src/RangeFilterChainNodelet.cc delete mode 100644 src/RelativeHumidityFilterChainNodelet.cc delete mode 100644 src/TemperatureFilterChainNodelet.cc diff --git a/CMakeLists.txt b/CMakeLists.txt index adf4200..bd34bb1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -4,130 +4,149 @@ cmake_minimum_required(VERSION 3.10.2) project(sensor_filters) +# TODO 2026-02-23 (solonovamax): clean all this up + set(CMAKE_CXX_STANDARD 17) -find_package(catkin REQUIRED COMPONENTS - filters - image_transport - nodelet - point_cloud_transport - roscpp - sensor_msgs +if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif () + +set(DEPENDENCIES robot_body_filter_msgs + backward_ros + filters + image_transport + point_cloud_transport + rclcpp + sensor_msgs ) -#catkin_lint: ignore missing_export_lib -catkin_package( - INCLUDE_DIRS include - CATKIN_DEPENDS filters nodelet roscpp sensor_msgs -) +find_package(ament_cmake REQUIRED) -include_directories(include ${catkin_INCLUDE_DIRS}) +foreach (dependency IN ITEMS ${DEPENDENCIES}) + find_package(${dependency} REQUIRED) +endforeach () + +include_directories(include include/${PROJECT_NAME}) set(types - CompressedImage - Image - Imu - Joy - LaserScan - MultiEchoLaserScan - MagneticField - NavSatFix - PointCloud - PointCloud2 - Range - RelativeHumidity - Temperature + CompressedImage + Image + Imu + Joy + LaserScan + MultiEchoLaserScan + MagneticField + NavSatFix + PointCloud + PointCloud2 + Range + RelativeHumidity + Temperature ) -foreach(type IN LISTS types) - string(TOLOWER "${type}" type_lower) +foreach (type IN LISTS types) + string(TOLOWER "${type}" type_lower) + + set(node_name "${type_lower}_filter_chain") - set(nodelet_name "${type_lower}_filter_chain_nodelet") - set(node_name "${type_lower}_filter_chain") + list(APPEND NODE_TARGETS ${node_name}) - add_library(${nodelet_name} src/${type}FilterChainNodelet.cc) - add_dependencies(${nodelet_name} ${catkin_EXPORTED_TARGETS}) - target_link_libraries(${nodelet_name} ${catkin_LIBRARIES}) + # add_library(${node_name} src/${type}FilterChainNodelet.cc) + # #target_link_libraries(${nodelet_name} ${DEPENDENCIES}) + # ament_target_dependencies(${node_name} ${DEPENDENCIES}) - add_executable(${node_name} src/${type}FilterChainNode.cc) - add_dependencies(${node_name} ${catkin_EXPORTED_TARGETS}) - target_link_libraries(${node_name} ${catkin_LIBRARIES}) + add_executable(${node_name} src/${type}FilterChainNode.cc) + #target_link_libraries(${node_name} ${DEPENDENCIES}) + ament_target_dependencies(${node_name} ${DEPENDENCIES}) - install(TARGETS ${node_name} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) + # install(TARGETS ${node_name} + # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + # ) - install(TARGETS ${nodelet_name} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} - ) -endforeach() + install(TARGETS ${node_name} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION lib + ) +endforeach () # Additional sources for the targets that use custom transport -target_sources(image_filter_chain_nodelet PRIVATE src/ImageFilterChainBase.cc) +#target_sources(image_filter_chain_nodelet PRIVATE src/ImageFilterChainBase.cc) target_sources(image_filter_chain PRIVATE src/ImageFilterChainBase.cc) -target_sources(pointcloud2_filter_chain_nodelet PRIVATE src/PointCloud2FilterChainBase.cc) +#target_sources(pointcloud2_filter_chain_nodelet PRIVATE src/PointCloud2FilterChainBase.cc) target_sources(pointcloud2_filter_chain PRIVATE src/PointCloud2FilterChainBase.cc) -set(filters - ChangeHeaderFilter -) - -foreach(filter IN LISTS filters) - add_library(${filter} src/filters/${filter}.cc) - add_dependencies(${filter} ${catkin_EXPORTED_TARGETS}) - target_link_libraries(${filter} ${catkin_LIBRARIES}) - install(TARGETS ${filter} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} - ) - install(FILES - ${filter}.xml - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} - ) -endforeach() - -install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - FILES_MATCHING PATTERN "*.h" -) - -install(FILES - nodelets.xml - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# TODO 2026-02-23 (solonovamax): finish this +# +#set(filters +# ChangeHeaderFilter +#) +# +#foreach (filter IN LISTS filters) +# add_library(${filter} src/filters/${filter}.cc) +# add_dependencies(${filter} ${catkin_EXPORTED_TARGETS}) +# target_link_libraries(${filter} ${catkin_LIBRARIES}) +# install(TARGETS ${filter} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) +# install(FILES +# ${filter}.xml +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) +#endforeach () + +install( + DIRECTORY include/ + DESTINATION include ) -if (CATKIN_ENABLE_TESTING) - find_package(roslint REQUIRED) - - # catkin_lint - checks validity of package.xml and CMakeLists.txt - # ROS buildfarm calls this without any environment and with empty rosdep cache, - # so we have problems reading the list of packages from env - # see https://github.com/ros-infrastructure/ros_buildfarm/issues/923 - if(DEFINED ENV{ROS_HOME}) - #catkin_lint: ignore_once env_var - set(ROS_HOME "$ENV{ROS_HOME}") - else() - #catkin_lint: ignore_once env_var - set(ROS_HOME "$ENV{HOME}/.ros") - endif() - #catkin_lint: ignore_once env_var - if(DEFINED ENV{ROS_ROOT} AND EXISTS "${ROS_HOME}/rosdep/sources.cache") - roslint_custom(catkin_lint "-W2" .) - endif() - - # Roslint C++ - checks formatting and some other rules for C++ files - - file(GLOB_RECURSE ROSLINT_INCLUDE include/*.h include/*.hpp) - file(GLOB_RECURSE ROSLINT_SRC src/*.cc src/filters/*.cc src/filters/*.hh examples/*.cpp) - #file(GLOB_RECURSE ROSLINT_TEST test/*.cpp) - - set(ROSLINT_CPP_OPTS "--extensions=h,hpp,hh,c,cpp,cc;--linelength=120;--filter=\ - -build/header_guard,-readability/namespace,-whitespace/braces,-runtime/references,\ - -build/c++11,-readability/nolint,-readability/todo,-legal/copyright,-build/namespaces") - roslint_cpp(${ROSLINT_INCLUDE} ${ROSLINT_SRC}) - - roslint_add_test() -endif() +#install(TARGETS ${NODE_TARGETS} +# EXPORT export_${PROJECT_NAME} +# RUNTIME DESTINATION bin +# ARCHIVE DESTINATION lib +# LIBRARY DESTINATION lib +#) + +#if (CATKIN_ENABLE_TESTING) +# find_package(roslint REQUIRED) +# +# # catkin_lint - checks validity of package.xml and CMakeLists.txt +# # ROS buildfarm calls this without any environment and with empty rosdep cache, +# # so we have problems reading the list of packages from env +# # see https://github.com/ros-infrastructure/ros_buildfarm/issues/923 +# if (DEFINED ENV{ROS_HOME}) +# #catkin_lint: ignore_once env_var +# set(ROS_HOME "$ENV{ROS_HOME}") +# else () +# #catkin_lint: ignore_once env_var +# set(ROS_HOME "$ENV{HOME}/.ros") +# endif () +# #catkin_lint: ignore_once env_var +# if (DEFINED ENV{ROS_ROOT} AND EXISTS "${ROS_HOME}/rosdep/sources.cache") +# roslint_custom(catkin_lint "-W2" .) +# endif () +# +# # Roslint C++ - checks formatting and some other rules for C++ files +# +# file(GLOB_RECURSE ROSLINT_INCLUDE include/*.h include/*.hpp) +# file(GLOB_RECURSE ROSLINT_SRC src/*.cc src/filters/*.cc src/filters/*.hh examples/*.cpp) +# #file(GLOB_RECURSE ROSLINT_TEST test/*.cpp) +# +# set(ROSLINT_CPP_OPTS "--extensions=h,hpp,hh,c,cpp,cc;--linelength=120;--filter=\ +# -build/header_guard,-readability/namespace,-whitespace/braces,-runtime/references,\ +# -build/c++11,-readability/nolint,-readability/todo,-legal/copyright,-build/namespaces") +# roslint_cpp(${ROSLINT_INCLUDE} ${ROSLINT_SRC}) +# +# roslint_add_test() +#endif () + +#ament_export_include_directories(include include/${PROJECT_NAME}) +#ament_export_dependencies(${DEPENDENCIES}) +#ament_export_libraries(${PROJECT_NAME} ) +#ament_export_targets( +# export_${PROJECT_NAME} +#) +ament_package() diff --git a/include/sensor_filters/FilterChainBase.h b/include/sensor_filters/FilterChainBase.h index c3eca16..fdde8fc 100644 --- a/include/sensor_filters/FilterChainBase.h +++ b/include/sensor_filters/FilterChainBase.h @@ -9,16 +9,8 @@ */ #include - -#include - -#if ROS_VERSION_MINIMUM(1, 15, 0) +#include #include -#else - -#include - -#endif namespace sensor_filters @@ -28,79 +20,86 @@ template class FilterChainBase { protected: - ros::Subscriber inputSubscriber; - ros::Publisher outputPublisher; - ros::NodeHandle topicNodeHandle; + std::shared_ptr> inputSubscriber; + std::shared_ptr> outputPublisher; + rclcpp::Node::SharedPtr node; size_t inputQueueSize{10u}; size_t outputQueueSize{10u}; - bool useSharedPtrMessages{true}; + bool usePtrMessages{true}; filters::FilterChain filterChain; T msg; - typedef ros::message_traits::DataType DataType; - public: FilterChainBase() : - filterChain(std::string(DataType::value()).replace(std::string(DataType::value()).find('/'), 1, "::")) + filterChain(std::string(typeid(T).name())) { } virtual ~FilterChainBase() = default; -protected: virtual void initFilters( - const std::string& filterChainNamespace, ros::NodeHandle filterNodeHandle, ros::NodeHandle topicNodeHandle, - const bool useSharedPtrMessages, const size_t inputQueueSize, const size_t outputQueueSize) - { - if (!this->filterChain.configure(filterChainNamespace, filterNodeHandle)) - { - ROS_ERROR_STREAM("Configuration of filter chain for " - << DataType::value() << " is invalid, the chain will not be run."); + const std::string& filterChainNamespace, rclcpp::Node::SharedPtr node, + const bool usePtrMessages, long inputQueueSize, long outputQueueSize) { + if (!this->filterChain.configure(filterChainNamespace, node->get_node_logging_interface(), node->get_node_parameters_interface())) { + RCLCPP_ERROR_STREAM(node->get_logger(), "Configuration of filter chain for " + << typeid(T).name() << " is invalid, the chain will not be run."); throw std::runtime_error("Filter configuration error"); } - ROS_INFO_STREAM("Configured filter chain of type " << DataType::value() << " from namespace " - << filterNodeHandle.getNamespace() << "/" - << filterChainNamespace); + RCLCPP_INFO_STREAM(node->get_logger(), "Configured filter chain of type " << typeid(T).name() << " from namespace " + << node->get_namespace() << "/" + << filterChainNamespace); - this->topicNodeHandle = topicNodeHandle; + this->node = node; this->outputQueueSize = outputQueueSize; this->inputQueueSize = inputQueueSize; - this->useSharedPtrMessages = useSharedPtrMessages; + this->usePtrMessages = usePtrMessages; this->advertise(); this->subscribe(); } +protected: + virtual void advertise() { - this->outputPublisher = this->topicNodeHandle.template advertise("output", this->outputQueueSize); + this->outputPublisher = this->node->create_publisher("output", this->outputQueueSize); } - virtual void subscribe() - { - if (this->useSharedPtrMessages) - this->inputSubscriber = this->topicNodeHandle.subscribe( - "input", this->inputQueueSize, &FilterChainBase::callbackShared, this); - else - this->inputSubscriber = this->topicNodeHandle.subscribe( - "input", this->inputQueueSize, &FilterChainBase::callbackReference, this); + virtual void subscribe() { + if (this->usePtrMessages) + this->inputSubscriber = this->node->template create_subscription( + "input", this->inputQueueSize, [this](const typename T::UniquePtr& msg) { + FilterChainBase::callbackUnique(msg); + }); + else + this->inputSubscriber = this->node->template create_subscription( + "input", this->inputQueueSize, [this](const T& msg) { + FilterChainBase::callbackReference(msg); + }); } - virtual void publishShared(const typename T::ConstPtr& msg) - { - this->outputPublisher.publish(msg); + virtual void publishUnique(typename T::UniquePtr& msg) { + this->outputPublisher->publish(std::move(msg)); } - virtual void publishReference(const T& msg) - { - this->outputPublisher.publish(msg); + virtual void publishShared(const typename T::ConstSharedPtr& msg) { + RCLCPP_ERROR_THROTTLE(node->get_logger(), *node->get_clock(), 1000, "must be overriden by child class"); } - virtual void callbackShared(const typename T::ConstPtr& msgIn) - { - typename T::Ptr msgOut(new T); + virtual void publishReference(const T& msg) { + this->outputPublisher->publish(msg); + } + + virtual void callbackUnique(const typename T::UniquePtr& msgIn) { + typename T::UniquePtr msgOut = std::make_unique(); + if (this->filter(*msgIn, *msgOut)) + this->publishUnique(msgOut); + } + + virtual void callbackShared(const typename T::ConstSharedPtr& msgIn) { + typename T::SharedPtr msgOut = std::make_shared(); if (this->filter(*msgIn, *msgOut)) this->publishShared(msgOut); } @@ -111,16 +110,15 @@ class FilterChainBase this->publishReference(this->msg); } - virtual bool filter(const T& msgIn, T& msgOut) - { - ros::WallTime start = ros::WallTime::now(); - if (!this->filterChain.update(msgIn, msgOut)) - { - ROS_ERROR_THROTTLE(1, "Filtering data from time %i.%i failed.", - msgIn.header.stamp.sec, msgIn.header.stamp.nsec); + virtual bool filter(const T& msgIn, T& msgOut) { + const auto clock = node->get_clock(); + const auto start = clock->now(); + if (!this->filterChain.update(msgIn, msgOut)) { + RCLCPP_ERROR_THROTTLE(node->get_logger(), *clock, 1000, "Filtering data from time %i.%i failed.", + msgIn.header.stamp.sec, msgIn.header.stamp.nanosec); return false; } - ROS_DEBUG_STREAM("Filtering took " << (ros::WallTime::now() - start).toSec() << " s."); + RCLCPP_DEBUG_STREAM(node->get_logger(), "Filtering took " << (clock->now() - start).seconds() << " s."); return true; } }; diff --git a/include/sensor_filters/FilterChainNode.h b/include/sensor_filters/FilterChainNode.h index 2b90067..610a4c8 100644 --- a/include/sensor_filters/FilterChainNode.h +++ b/include/sensor_filters/FilterChainNode.h @@ -16,27 +16,22 @@ namespace sensor_filters { template > -class FilterChainNode : public Base -{ +class FilterChainNode : public rclcpp::Node, public Base { public: - explicit FilterChainNode(const std::string& filterChainNamespace, ros::NodeHandle filterNodeHandle, - ros::NodeHandle topicNodeHandle) : Base() - { - this->initFilters( - filterChainNamespace, filterNodeHandle, topicNodeHandle, false, - filterNodeHandle.param("input_queue_size", 10), - filterNodeHandle.param("output_queue_size", 10)); + explicit FilterChainNode() : Base(), Node("") { } }; template > -void spinFilterChain(const std::string& filterChainNamespace, int argc, char** argv) -{ - ros::init(argc, argv, "filter_chain"); - ros::NodeHandle nh("~"); - const FilterChainNode node(filterChainNamespace, nh, nh); - ros::spin(); +void spinFilterChain(const std::string& filterChainNamespace, int argc, char** argv) { + rclcpp::init(argc, argv); + const auto node = std::make_shared>(); + node->initFilters( + filterChainNamespace, node, false, + node->declare_parameter("input_queue_size", 10), + node->declare_parameter("output_queue_size", 10)); + rclcpp::spin(node); } } diff --git a/include/sensor_filters/FilterChainNodelet.h b/include/sensor_filters/FilterChainNodelet.h deleted file mode 100644 index 7655042..0000000 --- a/include/sensor_filters/FilterChainNodelet.h +++ /dev/null @@ -1,58 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#pragma once - -/** - * \file - * \brief Base for all sensor filter chain nodelets. - */ - -#include -#include - -#include - -#include - -namespace sensor_filters -{ - -template> -class FilterChainNodelet : public nodelet::Nodelet, public Base -{ -protected: - std::string filterChainNamespace; - -public: - explicit FilterChainNodelet(std::string filterChainNamespace) : - nodelet::Nodelet(), Base(), filterChainNamespace(std::move(filterChainNamespace)) - { - } - - ~FilterChainNodelet() override = default; - -protected: - void onInit() override - { - this->initFilters( - this->filterChainNamespace, this->getPrivateNodeHandle(), this->getPrivateNodeHandle(), true, - this->getPrivateNodeHandle().param("input_queue_size", 10), - this->getPrivateNodeHandle().param("output_queue_size", 10)); - } -}; - -} - -#define DECLARE_SENSOR_FILTER_BASE(TYPE, BASE, CONFIG) \ -namespace sensor_filters \ -{ \ -class TYPE ## FilterChainNodelet : public FilterChainNodelet \ -{ \ - public: TYPE ## FilterChainNodelet() : FilterChainNodelet(CONFIG "_filter_chain") {} \ -}; \ -}\ -PLUGINLIB_EXPORT_CLASS(sensor_filters::TYPE ## FilterChainNodelet, nodelet::Nodelet) - -#define DECLARE_SENSOR_FILTER(TYPE, CONFIG) \ -DECLARE_SENSOR_FILTER_BASE(TYPE, sensor_filters::FilterChainBase, CONFIG) diff --git a/include/sensor_filters/ImageFilterChainBase.h b/include/sensor_filters/ImageFilterChainBase.h index 8f2228c..c1db265 100644 --- a/include/sensor_filters/ImageFilterChainBase.h +++ b/include/sensor_filters/ImageFilterChainBase.h @@ -14,33 +14,30 @@ #include #include #include -#include +#include #include namespace sensor_filters { -class ImageFilterChainBase : public FilterChainBase -{ +class ImageFilterChainBase : public FilterChainBase { public: - ImageFilterChainBase() : FilterChainBase() - { + ImageFilterChainBase() : FilterChainBase() { } + void initFilters(const std::string& filterChainNamespace, rclcpp::Node::SharedPtr node, + bool useSharedPtrMessages, long inputQueueSize, long outputQueueSize) override; + protected: std::unique_ptr it; image_transport::Publisher itPublisher; image_transport::Subscriber itSubscriber; - void initFilters(const std::string& filterChainNamespace, ros::NodeHandle filterNodeHandle, - ros::NodeHandle topicNodeHandle, bool useSharedPtrMessages, size_t inputQueueSize, - size_t outputQueueSize) override; - void advertise() override; void subscribe() override; - void publishShared(const sensor_msgs::ImageConstPtr& msg) override; + void publishShared(const sensor_msgs::msg::Image::ConstSharedPtr& msg) override; }; } diff --git a/include/sensor_filters/PointCloud2FilterChainBase.h b/include/sensor_filters/PointCloud2FilterChainBase.h index f241c21..a5dfcdc 100644 --- a/include/sensor_filters/PointCloud2FilterChainBase.h +++ b/include/sensor_filters/PointCloud2FilterChainBase.h @@ -11,36 +11,33 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include namespace sensor_filters { -class PointCloud2FilterChainBase : public FilterChainBase -{ +class PointCloud2FilterChainBase : public FilterChainBase { public: - PointCloud2FilterChainBase() : FilterChainBase() - { + PointCloud2FilterChainBase() : FilterChainBase() { } + void initFilters(const std::string& filterChainNamespace, rclcpp::Node::SharedPtr node, + bool useSharedPtrMessages, long inputQueueSize, long outputQueueSize) override; + protected: std::unique_ptr pct; point_cloud_transport::Publisher pctPublisher; point_cloud_transport::Subscriber pctSubscriber; - void initFilters(const std::string& filterChainNamespace, ros::NodeHandle filterNodeHandle, - ros::NodeHandle topicNodeHandle, bool useSharedPtrMessages, size_t inputQueueSize, - size_t outputQueueSize) override; - void advertise() override; void subscribe() override; - void publishShared(const sensor_msgs::PointCloud2ConstPtr& msg) override; + void publishShared(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) override; }; } diff --git a/nodelets.xml b/nodelets.xml deleted file mode 100644 index a0e08a3..0000000 --- a/nodelets.xml +++ /dev/null @@ -1,95 +0,0 @@ - - - - - Nodelet running a CompressedImage filter chain. - - - - - - - Nodelet running a Image filter chain. - - - - - - - Nodelet running a Imu filter chain. - - - - - - - Nodelet running a Joy filter chain. - - - - - - - Nodelet running a LaserScan filter chain. - - - - - - - Nodelet running a MagneticField filter chain. - - - - - - - Nodelet running a MultiEchoLaserScan filter chain. - - - - - - - Nodelet running a NavSatFix filter chain. - - - - - - - Nodelet running a PointCloud filter chain. - - - - - - - Nodelet running a PointCloud2 filter chain. - - - - - - - Nodelet running a Range filter chain. - - - - - - - Nodelet running a RelativeHumidity filter chain. - - - - - - - Nodelet running a Temperature filter chain. - - - diff --git a/src/CompressedImageFilterChainNode.cc b/src/CompressedImageFilterChainNode.cc index 69074d8..5ab8848 100644 --- a/src/CompressedImageFilterChainNode.cc +++ b/src/CompressedImageFilterChainNode.cc @@ -1,11 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain("image_filter_chain", argc, argv); +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain("image_filter_chain", argc, argv); } diff --git a/src/CompressedImageFilterChainNodelet.cc b/src/CompressedImageFilterChainNodelet.cc deleted file mode 100644 index f5b2dc4..0000000 --- a/src/CompressedImageFilterChainNodelet.cc +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include - -DECLARE_SENSOR_FILTER(CompressedImage, "image") // NOLINT(cert-err58-cpp) diff --git a/src/ImageFilterChainBase.cc b/src/ImageFilterChainBase.cc index bff01df..a21de4b 100644 --- a/src/ImageFilterChainBase.cc +++ b/src/ImageFilterChainBase.cc @@ -4,9 +4,8 @@ #include #include -#include -#include -#include +#include +#include #include #include @@ -14,29 +13,29 @@ namespace sensor_filters { -void ImageFilterChainBase::initFilters(const std::string& filterChainNamespace, ros::NodeHandle filterNodeHandle, - ros::NodeHandle topicNodeHandle, const bool useSharedPtrMessages, - const size_t inputQueueSize, const size_t outputQueueSize) +void ImageFilterChainBase::initFilters(const std::string& filterChainNamespace, rclcpp::Node::SharedPtr node, + const bool useSharedPtrMessages, const long inputQueueSize, const long outputQueueSize) { - this->it = std::make_unique(topicNodeHandle); - FilterChainBase::initFilters(filterChainNamespace, filterNodeHandle, topicNodeHandle, useSharedPtrMessages, + // TODO 2026-02-23 (solonovamax): offer parameter to advertise camera topic? + this->it = std::make_unique(node); + FilterChainBase::initFilters(filterChainNamespace, node, useSharedPtrMessages, inputQueueSize, outputQueueSize); } void ImageFilterChainBase::advertise() { - const auto resolvedOutput = this->topicNodeHandle.resolveName("output"); - this->itPublisher = this->it->advertise(resolvedOutput, this->outputQueueSize); + this->itPublisher = this->it->advertise("output", this->outputQueueSize); } void ImageFilterChainBase::subscribe() { - const auto resolvedInput = this->topicNodeHandle.resolveName("input"); - this->itSubscriber = this->it->subscribe( - resolvedInput, this->inputQueueSize, &ImageFilterChainBase::callbackShared, this); + this->itSubscriber = this->it->subscribe( + "input", this->inputQueueSize, [this](const typename sensor_msgs::msg::Image::ConstSharedPtr& msg) { + this->callbackShared(msg); + }); } -void ImageFilterChainBase::publishShared(const sensor_msgs::ImageConstPtr& msg) +void ImageFilterChainBase::publishShared(const sensor_msgs::msg::Image::ConstSharedPtr& msg) { this->itPublisher.publish(msg); } diff --git a/src/ImageFilterChainNode.cc b/src/ImageFilterChainNode.cc index ed29322..752b7eb 100644 --- a/src/ImageFilterChainNode.cc +++ b/src/ImageFilterChainNode.cc @@ -1,13 +1,12 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain( +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain( "image_filter_chain", argc, argv); } diff --git a/src/ImageFilterChainNodelet.cc b/src/ImageFilterChainNodelet.cc deleted file mode 100644 index 1269f7c..0000000 --- a/src/ImageFilterChainNodelet.cc +++ /dev/null @@ -1,10 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include -#include - -DECLARE_SENSOR_FILTER_BASE(Image, ImageFilterChainBase, "image") // NOLINT(cert-err58-cpp) diff --git a/src/ImuFilterChainNode.cc b/src/ImuFilterChainNode.cc index 5839160..7f330f0 100644 --- a/src/ImuFilterChainNode.cc +++ b/src/ImuFilterChainNode.cc @@ -1,11 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain("imu_filter_chain", argc, argv); +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain("imu_filter_chain", argc, argv); } diff --git a/src/ImuFilterChainNodelet.cc b/src/ImuFilterChainNodelet.cc deleted file mode 100644 index 445f6a3..0000000 --- a/src/ImuFilterChainNodelet.cc +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include - -DECLARE_SENSOR_FILTER(Imu, "imu") // NOLINT(cert-err58-cpp) diff --git a/src/JoyFilterChainNode.cc b/src/JoyFilterChainNode.cc index 7281657..dd40675 100644 --- a/src/JoyFilterChainNode.cc +++ b/src/JoyFilterChainNode.cc @@ -1,11 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain("joy_filter_chain", argc, argv); +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain("joy_filter_chain", argc, argv); } diff --git a/src/JoyFilterChainNodelet.cc b/src/JoyFilterChainNodelet.cc deleted file mode 100644 index 4e70967..0000000 --- a/src/JoyFilterChainNodelet.cc +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include - -DECLARE_SENSOR_FILTER(Joy, "joy") // NOLINT(cert-err58-cpp) diff --git a/src/LaserScanFilterChainNode.cc b/src/LaserScanFilterChainNode.cc index dacd4bd..ec030be 100644 --- a/src/LaserScanFilterChainNode.cc +++ b/src/LaserScanFilterChainNode.cc @@ -1,11 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain("scan_filter_chain", argc, argv); +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain("scan_filter_chain", argc, argv); } diff --git a/src/LaserScanFilterChainNodelet.cc b/src/LaserScanFilterChainNodelet.cc deleted file mode 100644 index ffeb226..0000000 --- a/src/LaserScanFilterChainNodelet.cc +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include - -DECLARE_SENSOR_FILTER(LaserScan, "scan") // NOLINT(cert-err58-cpp) diff --git a/src/MagneticFieldFilterChainNode.cc b/src/MagneticFieldFilterChainNode.cc index 8d4fced..1f31267 100644 --- a/src/MagneticFieldFilterChainNode.cc +++ b/src/MagneticFieldFilterChainNode.cc @@ -1,11 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain("magnetic_field_filter_chain", argc, argv); +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain("magnetic_field_filter_chain", argc, argv); } diff --git a/src/MagneticFieldFilterChainNodelet.cc b/src/MagneticFieldFilterChainNodelet.cc deleted file mode 100644 index 02aaeb6..0000000 --- a/src/MagneticFieldFilterChainNodelet.cc +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include - -DECLARE_SENSOR_FILTER(MagneticField, "magnetic_field") // NOLINT(cert-err58-cpp) diff --git a/src/MultiEchoLaserScanFilterChainNode.cc b/src/MultiEchoLaserScanFilterChainNode.cc index ae36412..6cfc035 100644 --- a/src/MultiEchoLaserScanFilterChainNode.cc +++ b/src/MultiEchoLaserScanFilterChainNode.cc @@ -1,11 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain("scan_filter_chain", argc, argv); +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain("scan_filter_chain", argc, argv); } diff --git a/src/MultiEchoLaserScanFilterChainNodelet.cc b/src/MultiEchoLaserScanFilterChainNodelet.cc deleted file mode 100644 index 55bf3d0..0000000 --- a/src/MultiEchoLaserScanFilterChainNodelet.cc +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include - -DECLARE_SENSOR_FILTER(MultiEchoLaserScan, "scan") // NOLINT(cert-err58-cpp) diff --git a/src/NavSatFixFilterChainNode.cc b/src/NavSatFixFilterChainNode.cc index b959e36..93ebfa7 100644 --- a/src/NavSatFixFilterChainNode.cc +++ b/src/NavSatFixFilterChainNode.cc @@ -1,11 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain("nav_sat_fix_filter_chain", argc, argv); +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain("nav_sat_fix_filter_chain", argc, argv); } diff --git a/src/NavSatFixFilterChainNodelet.cc b/src/NavSatFixFilterChainNodelet.cc deleted file mode 100644 index 395d13a..0000000 --- a/src/NavSatFixFilterChainNodelet.cc +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include - -DECLARE_SENSOR_FILTER(NavSatFix, "nav_sat_fix") // NOLINT(cert-err58-cpp) diff --git a/src/PointCloud2FilterChainBase.cc b/src/PointCloud2FilterChainBase.cc index e3e2910..7913b96 100644 --- a/src/PointCloud2FilterChainBase.cc +++ b/src/PointCloud2FilterChainBase.cc @@ -4,9 +4,8 @@ #include #include -#include -#include -#include +#include +#include #include #include @@ -14,31 +13,29 @@ namespace sensor_filters { -void PointCloud2FilterChainBase::initFilters(const std::string& filterChainNamespace, ros::NodeHandle filterNodeHandle, - ros::NodeHandle topicNodeHandle, const bool useSharedPtrMessages, - const size_t inputQueueSize, const size_t outputQueueSize) +void PointCloud2FilterChainBase::initFilters(const std::string& filterChainNamespace, rclcpp::Node::SharedPtr node, + const bool useSharedPtrMessages, const long inputQueueSize, const long outputQueueSize) { - this->pct = std::make_unique(topicNodeHandle); - FilterChainBase::initFilters(filterChainNamespace, filterNodeHandle, topicNodeHandle, useSharedPtrMessages, + this->pct = std::make_unique(node); + FilterChainBase::initFilters(filterChainNamespace, node, useSharedPtrMessages, inputQueueSize, outputQueueSize); } void PointCloud2FilterChainBase::advertise() { - const auto resolvedOutput = this->topicNodeHandle.resolveName("output"); - this->pctPublisher = this->pct->advertise(resolvedOutput, this->outputQueueSize); + this->pctPublisher = this->pct->advertise("output", this->outputQueueSize); } void PointCloud2FilterChainBase::subscribe() { - const auto resolvedInput = this->topicNodeHandle.resolveName("input"); - this->pctSubscriber = this->pct->subscribe( - resolvedInput, this->inputQueueSize, &PointCloud2FilterChainBase::callbackShared, this); + this->pctSubscriber = this->pct->subscribe( + "input", this->inputQueueSize, [this](const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) { + PointCloud2FilterChainBase::callbackShared(msg); + }); } -void PointCloud2FilterChainBase::publishShared(const sensor_msgs::PointCloud2ConstPtr& msg) +void PointCloud2FilterChainBase::publishShared(const typename sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) { this->pctPublisher.publish(msg); } - } diff --git a/src/PointCloud2FilterChainNode.cc b/src/PointCloud2FilterChainNode.cc index 84b98a2..5189521 100644 --- a/src/PointCloud2FilterChainNode.cc +++ b/src/PointCloud2FilterChainNode.cc @@ -1,13 +1,12 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain( +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain( "cloud_filter_chain", argc, argv); } diff --git a/src/PointCloud2FilterChainNodelet.cc b/src/PointCloud2FilterChainNodelet.cc deleted file mode 100644 index aa9bb18..0000000 --- a/src/PointCloud2FilterChainNodelet.cc +++ /dev/null @@ -1,10 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include -#include - -DECLARE_SENSOR_FILTER_BASE(PointCloud2, PointCloud2FilterChainBase, "cloud") // NOLINT(cert-err58-cpp) diff --git a/src/PointCloudFilterChainNode.cc b/src/PointCloudFilterChainNode.cc index 3dc03c6..8f65672 100644 --- a/src/PointCloudFilterChainNode.cc +++ b/src/PointCloudFilterChainNode.cc @@ -1,11 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain("cloud_filter_chain", argc, argv); +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain("cloud_filter_chain", argc, argv); } diff --git a/src/PointCloudFilterChainNodelet.cc b/src/PointCloudFilterChainNodelet.cc deleted file mode 100644 index e57604e..0000000 --- a/src/PointCloudFilterChainNodelet.cc +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include - -DECLARE_SENSOR_FILTER(PointCloud, "cloud") // NOLINT(cert-err58-cpp) diff --git a/src/RangeFilterChainNode.cc b/src/RangeFilterChainNode.cc index 11ee7c5..d267502 100644 --- a/src/RangeFilterChainNode.cc +++ b/src/RangeFilterChainNode.cc @@ -1,11 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain("range_filter_chain", argc, argv); +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain("range_filter_chain", argc, argv); } diff --git a/src/RangeFilterChainNodelet.cc b/src/RangeFilterChainNodelet.cc deleted file mode 100644 index 4cff3b2..0000000 --- a/src/RangeFilterChainNodelet.cc +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include - -DECLARE_SENSOR_FILTER(Range, "range") // NOLINT(cert-err58-cpp) diff --git a/src/RelativeHumidityFilterChainNode.cc b/src/RelativeHumidityFilterChainNode.cc index 3e33d47..4ec2d65 100644 --- a/src/RelativeHumidityFilterChainNode.cc +++ b/src/RelativeHumidityFilterChainNode.cc @@ -1,11 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain("humidity_filter_chain", argc, argv); +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain("humidity_filter_chain", argc, argv); } diff --git a/src/RelativeHumidityFilterChainNodelet.cc b/src/RelativeHumidityFilterChainNodelet.cc deleted file mode 100644 index 439526f..0000000 --- a/src/RelativeHumidityFilterChainNodelet.cc +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include - -DECLARE_SENSOR_FILTER(RelativeHumidity, "humidity") // NOLINT(cert-err58-cpp) diff --git a/src/TemperatureFilterChainNode.cc b/src/TemperatureFilterChainNode.cc index e9f7ef6..c657d85 100644 --- a/src/TemperatureFilterChainNode.cc +++ b/src/TemperatureFilterChainNode.cc @@ -1,11 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include -int main(int argc, char** argv) -{ - sensor_filters::spinFilterChain("temperature_filter_chain", argc, argv); +int main(const int argc, char** argv) { + sensor_filters::spinFilterChain("temperature_filter_chain", argc, argv); } diff --git a/src/TemperatureFilterChainNodelet.cc b/src/TemperatureFilterChainNodelet.cc deleted file mode 100644 index 4b66579..0000000 --- a/src/TemperatureFilterChainNodelet.cc +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -#include - -DECLARE_SENSOR_FILTER(Temperature, "temperature") // NOLINT(cert-err58-cpp) From 555291e7451d455be34ca2bbc58e047d32707604 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Mon, 23 Feb 2026 22:22:22 -0500 Subject: [PATCH 02/23] code cleanup Signed-off-by: solonovamax --- include/sensor_filters/FilterChainBase.h | 223 +++++++++--------- include/sensor_filters/FilterChainNode.h | 41 ++-- include/sensor_filters/ImageFilterChainBase.h | 40 ++-- .../PointCloud2FilterChainBase.h | 40 ++-- src/CompressedImageFilterChainNode.cc | 5 +- src/ImageFilterChainBase.cc | 63 +++-- src/ImageFilterChainNode.cc | 7 +- src/ImuFilterChainNode.cc | 5 +- src/JoyFilterChainNode.cc | 5 +- src/LaserScanFilterChainNode.cc | 5 +- src/MagneticFieldFilterChainNode.cc | 5 +- src/MultiEchoLaserScanFilterChainNode.cc | 5 +- src/NavSatFixFilterChainNode.cc | 5 +- src/PointCloud2FilterChainBase.cc | 59 +++-- src/PointCloud2FilterChainNode.cc | 6 +- src/PointCloudFilterChainNode.cc | 5 +- src/RangeFilterChainNode.cc | 5 +- src/RelativeHumidityFilterChainNode.cc | 5 +- src/TemperatureFilterChainNode.cc | 5 +- 19 files changed, 254 insertions(+), 280 deletions(-) diff --git a/include/sensor_filters/FilterChainBase.h b/include/sensor_filters/FilterChainBase.h index fdde8fc..e699efa 100644 --- a/include/sensor_filters/FilterChainBase.h +++ b/include/sensor_filters/FilterChainBase.h @@ -9,118 +9,117 @@ */ #include -#include #include +#include - -namespace sensor_filters -{ - -template -class FilterChainBase -{ -protected: - std::shared_ptr> inputSubscriber; - std::shared_ptr> outputPublisher; - rclcpp::Node::SharedPtr node; - size_t inputQueueSize{10u}; - size_t outputQueueSize{10u}; - bool usePtrMessages{true}; - - filters::FilterChain filterChain; - T msg; - -public: - FilterChainBase() : - filterChain(std::string(typeid(T).name())) - { - } - - virtual ~FilterChainBase() = default; - - virtual void initFilters( - const std::string& filterChainNamespace, rclcpp::Node::SharedPtr node, - const bool usePtrMessages, long inputQueueSize, long outputQueueSize) { - if (!this->filterChain.configure(filterChainNamespace, node->get_node_logging_interface(), node->get_node_parameters_interface())) { - RCLCPP_ERROR_STREAM(node->get_logger(), "Configuration of filter chain for " - << typeid(T).name() << " is invalid, the chain will not be run."); - throw std::runtime_error("Filter configuration error"); - } - - RCLCPP_INFO_STREAM(node->get_logger(), "Configured filter chain of type " << typeid(T).name() << " from namespace " - << node->get_namespace() << "/" - << filterChainNamespace); - - this->node = node; - this->outputQueueSize = outputQueueSize; - this->inputQueueSize = inputQueueSize; - this->usePtrMessages = usePtrMessages; - - this->advertise(); - this->subscribe(); - } - -protected: - - virtual void advertise() - { - this->outputPublisher = this->node->create_publisher("output", this->outputQueueSize); - } - - virtual void subscribe() { - if (this->usePtrMessages) - this->inputSubscriber = this->node->template create_subscription( - "input", this->inputQueueSize, [this](const typename T::UniquePtr& msg) { - FilterChainBase::callbackUnique(msg); - }); - else - this->inputSubscriber = this->node->template create_subscription( - "input", this->inputQueueSize, [this](const T& msg) { - FilterChainBase::callbackReference(msg); - }); - } - - virtual void publishUnique(typename T::UniquePtr& msg) { - this->outputPublisher->publish(std::move(msg)); - } - - virtual void publishShared(const typename T::ConstSharedPtr& msg) { - RCLCPP_ERROR_THROTTLE(node->get_logger(), *node->get_clock(), 1000, "must be overriden by child class"); - } - - virtual void publishReference(const T& msg) { - this->outputPublisher->publish(msg); - } - - virtual void callbackUnique(const typename T::UniquePtr& msgIn) { - typename T::UniquePtr msgOut = std::make_unique(); - if (this->filter(*msgIn, *msgOut)) - this->publishUnique(msgOut); - } - - virtual void callbackShared(const typename T::ConstSharedPtr& msgIn) { - typename T::SharedPtr msgOut = std::make_shared(); - if (this->filter(*msgIn, *msgOut)) - this->publishShared(msgOut); - } - - virtual void callbackReference(const T& msgIn) - { - if (this->filter(msgIn, this->msg)) - this->publishReference(this->msg); - } - - virtual bool filter(const T& msgIn, T& msgOut) { - const auto clock = node->get_clock(); - const auto start = clock->now(); - if (!this->filterChain.update(msgIn, msgOut)) { - RCLCPP_ERROR_THROTTLE(node->get_logger(), *clock, 1000, "Filtering data from time %i.%i failed.", - msgIn.header.stamp.sec, msgIn.header.stamp.nanosec); - return false; - } - RCLCPP_DEBUG_STREAM(node->get_logger(), "Filtering took " << (clock->now() - start).seconds() << " s."); - return true; - } -}; - +namespace sensor_filters { + template + class FilterChainBase { + protected: + std::shared_ptr> inputSubscriber; + std::shared_ptr> outputPublisher; + rclcpp::Node::SharedPtr node; + size_t inputQueueSize = 10u; + size_t outputQueueSize = 10u; + bool usePtrMessages = true; + + filters::FilterChain filterChain; + T msg; + + public: + FilterChainBase() : + filterChain(std::string(typeid(T).name())) {} + + virtual ~FilterChainBase() = default; + + virtual void initFilters( + const std::string& filterChainNamespace, + rclcpp::Node::SharedPtr node, + const bool usePtrMessages, + long inputQueueSize, + long outputQueueSize + ) { + if (!this->filterChain.configure(filterChainNamespace, node->get_node_logging_interface(), node->get_node_parameters_interface())) { + RCLCPP_ERROR_STREAM(node->get_logger(), "Configuration of filter chain for " + << typeid(T).name() << " is invalid, the chain will not be run."); + throw std::runtime_error("Filter configuration error"); + } + + RCLCPP_INFO_STREAM(node->get_logger(), "Configured filter chain of type " << typeid(T).name() << " from namespace " + << node->get_namespace() << "/" + << filterChainNamespace); + + this->node = node; + this->outputQueueSize = outputQueueSize; + this->inputQueueSize = inputQueueSize; + this->usePtrMessages = usePtrMessages; + + this->advertise(); + this->subscribe(); + } + + protected: + virtual void advertise() { + this->outputPublisher = this->node->create_publisher("output", this->outputQueueSize); + } + + virtual void subscribe() { + if (this->usePtrMessages) { + this->inputSubscriber = this->node->template create_subscription( + "input", this->inputQueueSize, + [this](const typename T::UniquePtr& msg) { + FilterChainBase::callbackUnique(msg); + } + ); + } else { + this->inputSubscriber = this->node->template create_subscription( + "input", this->inputQueueSize, + [this](const T& msg) { + FilterChainBase::callbackReference(msg); + } + ); + } + } + + virtual void publishUnique(typename T::UniquePtr& msg) { + this->outputPublisher->publish(std::move(msg)); + } + + virtual void publishShared(const typename T::ConstSharedPtr& msg) { + RCLCPP_ERROR_THROTTLE(node->get_logger(), *node->get_clock(), 1000, "must be overriden by child class"); + } + + virtual void publishReference(const T& msg) { + this->outputPublisher->publish(msg); + } + + virtual void callbackUnique(const typename T::UniquePtr& msgIn) { + typename T::UniquePtr msgOut = std::make_unique(); + if (this->filter(*msgIn, *msgOut)) + this->publishUnique(msgOut); + } + + virtual void callbackShared(const typename T::ConstSharedPtr& msgIn) { + typename T::SharedPtr msgOut = std::make_shared(); + if (this->filter(*msgIn, *msgOut)) + this->publishShared(msgOut); + } + + virtual void callbackReference(const T& msgIn) { + if (this->filter(msgIn, this->msg)) + this->publishReference(this->msg); + } + + virtual bool filter(const T& msgIn, T& msgOut) { + const auto clock = node->get_clock(); + const auto start = clock->now(); + if (!this->filterChain.update(msgIn, msgOut)) { + RCLCPP_ERROR_THROTTLE(node->get_logger(), *clock, 1000, "Filtering data from time %i.%i failed.", + msgIn.header.stamp.sec, msgIn.header.stamp.nanosec); + return false; + } + RCLCPP_DEBUG_STREAM(node->get_logger(), "Filtering took " << (clock->now() - start).seconds() << " s."); + return true; + } + }; } diff --git a/include/sensor_filters/FilterChainNode.h b/include/sensor_filters/FilterChainNode.h index 610a4c8..c2a3a71 100644 --- a/include/sensor_filters/FilterChainNode.h +++ b/include/sensor_filters/FilterChainNode.h @@ -9,29 +9,24 @@ */ #include - #include -namespace sensor_filters -{ - -template > -class FilterChainNode : public rclcpp::Node, public Base { -public: - explicit FilterChainNode() : Base(), Node("") { - } -}; - - -template > -void spinFilterChain(const std::string& filterChainNamespace, int argc, char** argv) { - rclcpp::init(argc, argv); - const auto node = std::make_shared>(); - node->initFilters( - filterChainNamespace, node, false, - node->declare_parameter("input_queue_size", 10), - node->declare_parameter("output_queue_size", 10)); - rclcpp::spin(node); -} - +namespace sensor_filters { + template > + class FilterChainNode : public rclcpp::Node, public Base { + public: + explicit FilterChainNode() : Base(), Node("") {} + }; + + + template > + void spinFilterChain(const std::string& filterChainNamespace, const int argc, char** argv) { + rclcpp::init(argc, argv); + const auto node = std::make_shared>(); + node->initFilters( + filterChainNamespace, node, false, + node->declare_parameter("input_queue_size", 10), + node->declare_parameter("output_queue_size", 10)); + rclcpp::spin(node); + } } diff --git a/include/sensor_filters/ImageFilterChainBase.h b/include/sensor_filters/ImageFilterChainBase.h index c1db265..d378d5c 100644 --- a/include/sensor_filters/ImageFilterChainBase.h +++ b/include/sensor_filters/ImageFilterChainBase.h @@ -10,34 +10,34 @@ #include #include - #include #include #include -#include - #include +#include -namespace sensor_filters -{ -class ImageFilterChainBase : public FilterChainBase { -public: - ImageFilterChainBase() : FilterChainBase() { - } - - void initFilters(const std::string& filterChainNamespace, rclcpp::Node::SharedPtr node, - bool useSharedPtrMessages, long inputQueueSize, long outputQueueSize) override; +namespace sensor_filters { + class ImageFilterChainBase : public FilterChainBase { + public: + ImageFilterChainBase() {} -protected: - std::unique_ptr it; - image_transport::Publisher itPublisher; - image_transport::Subscriber itSubscriber; + void initFilters( + const std::string& filterChainNamespace, + rclcpp::Node::SharedPtr node, + bool useSharedPtrMessages, + long inputQueueSize, + long outputQueueSize + ) override; - void advertise() override; + protected: + std::unique_ptr it; + image_transport::Publisher itPublisher; + image_transport::Subscriber itSubscriber; - void subscribe() override; + void advertise() override; - void publishShared(const sensor_msgs::msg::Image::ConstSharedPtr& msg) override; -}; + void subscribe() override; + void publishShared(const sensor_msgs::msg::Image::ConstSharedPtr& msg) override; + }; } diff --git a/include/sensor_filters/PointCloud2FilterChainBase.h b/include/sensor_filters/PointCloud2FilterChainBase.h index a5dfcdc..5e0ec19 100644 --- a/include/sensor_filters/PointCloud2FilterChainBase.h +++ b/include/sensor_filters/PointCloud2FilterChainBase.h @@ -10,34 +10,34 @@ #include #include - #include #include #include -#include - #include +#include -namespace sensor_filters -{ -class PointCloud2FilterChainBase : public FilterChainBase { -public: - PointCloud2FilterChainBase() : FilterChainBase() { - } - - void initFilters(const std::string& filterChainNamespace, rclcpp::Node::SharedPtr node, - bool useSharedPtrMessages, long inputQueueSize, long outputQueueSize) override; +namespace sensor_filters { + class PointCloud2FilterChainBase : public FilterChainBase { + public: + PointCloud2FilterChainBase() {} -protected: - std::unique_ptr pct; - point_cloud_transport::Publisher pctPublisher; - point_cloud_transport::Subscriber pctSubscriber; + void initFilters( + const std::string& filterChainNamespace, + rclcpp::Node::SharedPtr node, + bool useSharedPtrMessages, + long inputQueueSize, + long outputQueueSize + ) override; - void advertise() override; + protected: + std::unique_ptr pct; + point_cloud_transport::Publisher pctPublisher; + point_cloud_transport::Subscriber pctSubscriber; - void subscribe() override; + void advertise() override; - void publishShared(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) override; -}; + void subscribe() override; + void publishShared(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) override; + }; } diff --git a/src/CompressedImageFilterChainNode.cc b/src/CompressedImageFilterChainNode.cc index 5ab8848..a277b2c 100644 --- a/src/CompressedImageFilterChainNode.cc +++ b/src/CompressedImageFilterChainNode.cc @@ -1,10 +1,9 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("image_filter_chain", argc, argv); + sensor_filters::spinFilterChain("image_filter_chain", argc, argv); } diff --git a/src/ImageFilterChainBase.cc b/src/ImageFilterChainBase.cc index a21de4b..1d7209c 100644 --- a/src/ImageFilterChainBase.cc +++ b/src/ImageFilterChainBase.cc @@ -3,41 +3,38 @@ #include #include - #include -#include - #include #include +#include -namespace sensor_filters -{ - -void ImageFilterChainBase::initFilters(const std::string& filterChainNamespace, rclcpp::Node::SharedPtr node, - const bool useSharedPtrMessages, const long inputQueueSize, const long outputQueueSize) -{ - // TODO 2026-02-23 (solonovamax): offer parameter to advertise camera topic? - this->it = std::make_unique(node); - FilterChainBase::initFilters(filterChainNamespace, node, useSharedPtrMessages, - inputQueueSize, outputQueueSize); -} - -void ImageFilterChainBase::advertise() -{ - this->itPublisher = this->it->advertise("output", this->outputQueueSize); -} - -void ImageFilterChainBase::subscribe() -{ - this->itSubscriber = this->it->subscribe( - "input", this->inputQueueSize, [this](const typename sensor_msgs::msg::Image::ConstSharedPtr& msg) { - this->callbackShared(msg); - }); -} - -void ImageFilterChainBase::publishShared(const sensor_msgs::msg::Image::ConstSharedPtr& msg) -{ - this->itPublisher.publish(msg); -} - +namespace sensor_filters { + void ImageFilterChainBase::initFilters( + const std::string& filterChainNamespace, + rclcpp::Node::SharedPtr node, + const bool useSharedPtrMessages, + const long inputQueueSize, + const long outputQueueSize + ) { + // TODO 2026-02-23 (solonovamax): offer parameter to advertise camera topic? + this->it = std::make_unique(node); + FilterChainBase::initFilters(filterChainNamespace, node, useSharedPtrMessages, inputQueueSize, outputQueueSize); + } + + void ImageFilterChainBase::advertise() { + this->itPublisher = this->it->advertise("output", this->outputQueueSize); + } + + void ImageFilterChainBase::subscribe() { + this->itSubscriber = this->it->subscribe( + "input", this->inputQueueSize, + [this](const typename sensor_msgs::msg::Image::ConstSharedPtr& msg) { + this->callbackShared(msg); + } + ); + } + + void ImageFilterChainBase::publishShared(const sensor_msgs::msg::Image::ConstSharedPtr& msg) { + this->itPublisher.publish(msg); + } } diff --git a/src/ImageFilterChainNode.cc b/src/ImageFilterChainNode.cc index 752b7eb..bd02f26 100644 --- a/src/ImageFilterChainNode.cc +++ b/src/ImageFilterChainNode.cc @@ -1,12 +1,11 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain( - "image_filter_chain", argc, argv); + sensor_filters::spinFilterChain( + "image_filter_chain", argc, argv); } diff --git a/src/ImuFilterChainNode.cc b/src/ImuFilterChainNode.cc index 7f330f0..bcf755d 100644 --- a/src/ImuFilterChainNode.cc +++ b/src/ImuFilterChainNode.cc @@ -1,10 +1,9 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("imu_filter_chain", argc, argv); + sensor_filters::spinFilterChain("imu_filter_chain", argc, argv); } diff --git a/src/JoyFilterChainNode.cc b/src/JoyFilterChainNode.cc index dd40675..c7cfef3 100644 --- a/src/JoyFilterChainNode.cc +++ b/src/JoyFilterChainNode.cc @@ -1,10 +1,9 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("joy_filter_chain", argc, argv); + sensor_filters::spinFilterChain("joy_filter_chain", argc, argv); } diff --git a/src/LaserScanFilterChainNode.cc b/src/LaserScanFilterChainNode.cc index ec030be..ef51c6f 100644 --- a/src/LaserScanFilterChainNode.cc +++ b/src/LaserScanFilterChainNode.cc @@ -1,10 +1,9 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("scan_filter_chain", argc, argv); + sensor_filters::spinFilterChain("scan_filter_chain", argc, argv); } diff --git a/src/MagneticFieldFilterChainNode.cc b/src/MagneticFieldFilterChainNode.cc index 1f31267..4fe3f09 100644 --- a/src/MagneticFieldFilterChainNode.cc +++ b/src/MagneticFieldFilterChainNode.cc @@ -1,10 +1,9 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("magnetic_field_filter_chain", argc, argv); + sensor_filters::spinFilterChain("magnetic_field_filter_chain", argc, argv); } diff --git a/src/MultiEchoLaserScanFilterChainNode.cc b/src/MultiEchoLaserScanFilterChainNode.cc index 6cfc035..4ab063b 100644 --- a/src/MultiEchoLaserScanFilterChainNode.cc +++ b/src/MultiEchoLaserScanFilterChainNode.cc @@ -1,10 +1,9 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("scan_filter_chain", argc, argv); + sensor_filters::spinFilterChain("scan_filter_chain", argc, argv); } diff --git a/src/NavSatFixFilterChainNode.cc b/src/NavSatFixFilterChainNode.cc index 93ebfa7..f336789 100644 --- a/src/NavSatFixFilterChainNode.cc +++ b/src/NavSatFixFilterChainNode.cc @@ -1,10 +1,9 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("nav_sat_fix_filter_chain", argc, argv); + sensor_filters::spinFilterChain("nav_sat_fix_filter_chain", argc, argv); } diff --git a/src/PointCloud2FilterChainBase.cc b/src/PointCloud2FilterChainBase.cc index 7913b96..c2b538d 100644 --- a/src/PointCloud2FilterChainBase.cc +++ b/src/PointCloud2FilterChainBase.cc @@ -3,39 +3,36 @@ #include #include - #include -#include - #include #include -namespace sensor_filters -{ - -void PointCloud2FilterChainBase::initFilters(const std::string& filterChainNamespace, rclcpp::Node::SharedPtr node, - const bool useSharedPtrMessages, const long inputQueueSize, const long outputQueueSize) -{ - this->pct = std::make_unique(node); - FilterChainBase::initFilters(filterChainNamespace, node, useSharedPtrMessages, - inputQueueSize, outputQueueSize); -} - -void PointCloud2FilterChainBase::advertise() -{ - this->pctPublisher = this->pct->advertise("output", this->outputQueueSize); -} - -void PointCloud2FilterChainBase::subscribe() -{ - this->pctSubscriber = this->pct->subscribe( - "input", this->inputQueueSize, [this](const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) { - PointCloud2FilterChainBase::callbackShared(msg); - }); -} - -void PointCloud2FilterChainBase::publishShared(const typename sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) -{ - this->pctPublisher.publish(msg); -} +namespace sensor_filters { + void PointCloud2FilterChainBase::initFilters( + const std::string& filterChainNamespace, + rclcpp::Node::SharedPtr node, + const bool useSharedPtrMessages, + const long inputQueueSize, + const long outputQueueSize + ) { + this->pct = std::make_unique(node); + FilterChainBase::initFilters(filterChainNamespace, node, useSharedPtrMessages, inputQueueSize, outputQueueSize); + } + + void PointCloud2FilterChainBase::advertise() { + this->pctPublisher = this->pct->advertise("output", this->outputQueueSize); + } + + void PointCloud2FilterChainBase::subscribe() { + this->pctSubscriber = this->pct->subscribe( + "input", this->inputQueueSize, + [this](const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) { + PointCloud2FilterChainBase::callbackShared(msg); + } + ); + } + + void PointCloud2FilterChainBase::publishShared(const typename sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) { + this->pctPublisher.publish(msg); + } } diff --git a/src/PointCloud2FilterChainNode.cc b/src/PointCloud2FilterChainNode.cc index 5189521..2302f5a 100644 --- a/src/PointCloud2FilterChainNode.cc +++ b/src/PointCloud2FilterChainNode.cc @@ -1,12 +1,10 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain( - "cloud_filter_chain", argc, argv); + sensor_filters::spinFilterChain("cloud_filter_chain", argc, argv); } diff --git a/src/PointCloudFilterChainNode.cc b/src/PointCloudFilterChainNode.cc index 8f65672..038a6cb 100644 --- a/src/PointCloudFilterChainNode.cc +++ b/src/PointCloudFilterChainNode.cc @@ -1,10 +1,9 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("cloud_filter_chain", argc, argv); + sensor_filters::spinFilterChain("cloud_filter_chain", argc, argv); } diff --git a/src/RangeFilterChainNode.cc b/src/RangeFilterChainNode.cc index d267502..05a657c 100644 --- a/src/RangeFilterChainNode.cc +++ b/src/RangeFilterChainNode.cc @@ -1,10 +1,9 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("range_filter_chain", argc, argv); + sensor_filters::spinFilterChain("range_filter_chain", argc, argv); } diff --git a/src/RelativeHumidityFilterChainNode.cc b/src/RelativeHumidityFilterChainNode.cc index 4ec2d65..3eff349 100644 --- a/src/RelativeHumidityFilterChainNode.cc +++ b/src/RelativeHumidityFilterChainNode.cc @@ -1,10 +1,9 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("humidity_filter_chain", argc, argv); + sensor_filters::spinFilterChain("humidity_filter_chain", argc, argv); } diff --git a/src/TemperatureFilterChainNode.cc b/src/TemperatureFilterChainNode.cc index c657d85..5e1e8ce 100644 --- a/src/TemperatureFilterChainNode.cc +++ b/src/TemperatureFilterChainNode.cc @@ -1,10 +1,9 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include - #include +#include int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("temperature_filter_chain", argc, argv); + sensor_filters::spinFilterChain("temperature_filter_chain", argc, argv); } From 3cb530891504a19c7c7793f01b39912b470ed562 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Mon, 23 Feb 2026 22:39:29 -0500 Subject: [PATCH 03/23] rename .h -> .hpp & .cc -> .cpp Signed-off-by: solonovamax --- CMakeLists.txt | 16 +-- ...{FilterChainBase.h => FilterChainBase.hpp} | 0 ...{FilterChainNode.h => FilterChainNode.hpp} | 2 +- ...erChainBase.h => ImageFilterChainBase.hpp} | 2 +- ...nBase.h => PointCloud2FilterChainBase.hpp} | 2 +- ....cc => CompressedImageFilterChainNode.cpp} | 2 +- ...rChainBase.cc => ImageFilterChainBase.cpp} | 4 +- ...rChainNode.cc => ImageFilterChainNode.cpp} | 4 +- ...terChainNode.cc => ImuFilterChainNode.cpp} | 2 +- ...terChainNode.cc => JoyFilterChainNode.cpp} | 2 +- ...inNode.cc => LaserScanFilterChainNode.cpp} | 2 +- ...de.cc => MagneticFieldFilterChainNode.cpp} | 2 +- ... => MultiEchoLaserScanFilterChainNode.cpp} | 2 +- ...inNode.cc => NavSatFixFilterChainNode.cpp} | 2 +- ...Base.cc => PointCloud2FilterChainBase.cpp} | 4 +- ...Node.cc => PointCloud2FilterChainNode.cpp} | 4 +- ...nNode.cc => PointCloudFilterChainNode.cpp} | 2 +- ...rChainNode.cc => RangeFilterChainNode.cpp} | 2 +- ...cc => RelativeHumidityFilterChainNode.cpp} | 2 +- ...Node.cc => TemperatureFilterChainNode.cpp} | 2 +- src/filters/ChangeHeaderFilter.cc | 103 ------------------ src/filters/ChangeHeaderFilter.cpp | 97 +++++++++++++++++ ...clude_all_msgs.hh => include_all_msgs.hpp} | 0 23 files changed, 127 insertions(+), 133 deletions(-) rename include/sensor_filters/{FilterChainBase.h => FilterChainBase.hpp} (100%) rename include/sensor_filters/{FilterChainNode.h => FilterChainNode.hpp} (95%) rename include/sensor_filters/{ImageFilterChainBase.h => ImageFilterChainBase.hpp} (96%) rename include/sensor_filters/{PointCloud2FilterChainBase.h => PointCloud2FilterChainBase.hpp} (96%) rename src/{CompressedImageFilterChainNode.cc => CompressedImageFilterChainNode.cpp} (86%) rename src/{ImageFilterChainBase.cc => ImageFilterChainBase.cpp} (93%) rename src/{ImageFilterChainNode.cc => ImageFilterChainNode.cpp} (77%) rename src/{ImuFilterChainNode.cc => ImuFilterChainNode.cpp} (85%) rename src/{JoyFilterChainNode.cc => JoyFilterChainNode.cpp} (85%) rename src/{LaserScanFilterChainNode.cc => LaserScanFilterChainNode.cpp} (86%) rename src/{MagneticFieldFilterChainNode.cc => MagneticFieldFilterChainNode.cpp} (87%) rename src/{MultiEchoLaserScanFilterChainNode.cc => MultiEchoLaserScanFilterChainNode.cpp} (87%) rename src/{NavSatFixFilterChainNode.cc => NavSatFixFilterChainNode.cpp} (86%) rename src/{PointCloud2FilterChainBase.cc => PointCloud2FilterChainBase.cpp} (92%) rename src/{PointCloud2FilterChainNode.cc => PointCloud2FilterChainNode.cpp} (76%) rename src/{PointCloudFilterChainNode.cc => PointCloudFilterChainNode.cpp} (86%) rename src/{RangeFilterChainNode.cc => RangeFilterChainNode.cpp} (85%) rename src/{RelativeHumidityFilterChainNode.cc => RelativeHumidityFilterChainNode.cpp} (87%) rename src/{TemperatureFilterChainNode.cc => TemperatureFilterChainNode.cpp} (86%) delete mode 100644 src/filters/ChangeHeaderFilter.cc create mode 100644 src/filters/ChangeHeaderFilter.cpp rename src/filters/{include_all_msgs.hh => include_all_msgs.hpp} (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index bd34bb1..52b03b8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -52,11 +52,11 @@ foreach (type IN LISTS types) list(APPEND NODE_TARGETS ${node_name}) - # add_library(${node_name} src/${type}FilterChainNodelet.cc) + # add_library(${node_name} src/${type}FilterChainNodelet.cpp) # #target_link_libraries(${nodelet_name} ${DEPENDENCIES}) # ament_target_dependencies(${node_name} ${DEPENDENCIES}) - add_executable(${node_name} src/${type}FilterChainNode.cc) + add_executable(${node_name} src/${type}FilterChainNode.cpp) #target_link_libraries(${node_name} ${DEPENDENCIES}) ament_target_dependencies(${node_name} ${DEPENDENCIES}) @@ -72,10 +72,10 @@ foreach (type IN LISTS types) endforeach () # Additional sources for the targets that use custom transport -#target_sources(image_filter_chain_nodelet PRIVATE src/ImageFilterChainBase.cc) -target_sources(image_filter_chain PRIVATE src/ImageFilterChainBase.cc) -#target_sources(pointcloud2_filter_chain_nodelet PRIVATE src/PointCloud2FilterChainBase.cc) -target_sources(pointcloud2_filter_chain PRIVATE src/PointCloud2FilterChainBase.cc) +#target_sources(image_filter_chain_nodelet PRIVATE src/ImageFilterChainBase.cpp) +target_sources(image_filter_chain PRIVATE src/ImageFilterChainBase.cpp) +#target_sources(pointcloud2_filter_chain_nodelet PRIVATE src/PointCloud2FilterChainBase.cpp) +target_sources(pointcloud2_filter_chain PRIVATE src/PointCloud2FilterChainBase.cpp) # TODO 2026-02-23 (solonovamax): finish this # @@ -84,7 +84,7 @@ target_sources(pointcloud2_filter_chain PRIVATE src/PointCloud2FilterChainBase.c #) # #foreach (filter IN LISTS filters) -# add_library(${filter} src/filters/${filter}.cc) +# add_library(${filter} src/filters/${filter}.cpp) # add_dependencies(${filter} ${catkin_EXPORTED_TARGETS}) # target_link_libraries(${filter} ${catkin_LIBRARIES}) # install(TARGETS ${filter} @@ -132,7 +132,7 @@ install( # # Roslint C++ - checks formatting and some other rules for C++ files # # file(GLOB_RECURSE ROSLINT_INCLUDE include/*.h include/*.hpp) -# file(GLOB_RECURSE ROSLINT_SRC src/*.cc src/filters/*.cc src/filters/*.hh examples/*.cpp) +# file(GLOB_RECURSE ROSLINT_SRC src/*.cpp src/filters/*.cpp src/filters/*.hpp examples/*.cpp) # #file(GLOB_RECURSE ROSLINT_TEST test/*.cpp) # # set(ROSLINT_CPP_OPTS "--extensions=h,hpp,hh,c,cpp,cc;--linelength=120;--filter=\ diff --git a/include/sensor_filters/FilterChainBase.h b/include/sensor_filters/FilterChainBase.hpp similarity index 100% rename from include/sensor_filters/FilterChainBase.h rename to include/sensor_filters/FilterChainBase.hpp diff --git a/include/sensor_filters/FilterChainNode.h b/include/sensor_filters/FilterChainNode.hpp similarity index 95% rename from include/sensor_filters/FilterChainNode.h rename to include/sensor_filters/FilterChainNode.hpp index c2a3a71..b19e7c9 100644 --- a/include/sensor_filters/FilterChainNode.h +++ b/include/sensor_filters/FilterChainNode.hpp @@ -9,7 +9,7 @@ */ #include -#include +#include namespace sensor_filters { template > diff --git a/include/sensor_filters/ImageFilterChainBase.h b/include/sensor_filters/ImageFilterChainBase.hpp similarity index 96% rename from include/sensor_filters/ImageFilterChainBase.h rename to include/sensor_filters/ImageFilterChainBase.hpp index d378d5c..9826384 100644 --- a/include/sensor_filters/ImageFilterChainBase.h +++ b/include/sensor_filters/ImageFilterChainBase.hpp @@ -13,7 +13,7 @@ #include #include #include -#include +#include #include namespace sensor_filters { diff --git a/include/sensor_filters/PointCloud2FilterChainBase.h b/include/sensor_filters/PointCloud2FilterChainBase.hpp similarity index 96% rename from include/sensor_filters/PointCloud2FilterChainBase.h rename to include/sensor_filters/PointCloud2FilterChainBase.hpp index 5e0ec19..0b8929e 100644 --- a/include/sensor_filters/PointCloud2FilterChainBase.h +++ b/include/sensor_filters/PointCloud2FilterChainBase.hpp @@ -13,7 +13,7 @@ #include #include #include -#include +#include #include namespace sensor_filters { diff --git a/src/CompressedImageFilterChainNode.cc b/src/CompressedImageFilterChainNode.cpp similarity index 86% rename from src/CompressedImageFilterChainNode.cc rename to src/CompressedImageFilterChainNode.cpp index a277b2c..bf63134 100644 --- a/src/CompressedImageFilterChainNode.cc +++ b/src/CompressedImageFilterChainNode.cpp @@ -1,7 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include int main(const int argc, char** argv) { diff --git a/src/ImageFilterChainBase.cc b/src/ImageFilterChainBase.cpp similarity index 93% rename from src/ImageFilterChainBase.cc rename to src/ImageFilterChainBase.cpp index 1d7209c..6967eb3 100644 --- a/src/ImageFilterChainBase.cc +++ b/src/ImageFilterChainBase.cpp @@ -4,8 +4,8 @@ #include #include #include -#include -#include +#include +#include #include namespace sensor_filters { diff --git a/src/ImageFilterChainNode.cc b/src/ImageFilterChainNode.cpp similarity index 77% rename from src/ImageFilterChainNode.cc rename to src/ImageFilterChainNode.cpp index bd02f26..a1015bf 100644 --- a/src/ImageFilterChainNode.cc +++ b/src/ImageFilterChainNode.cpp @@ -1,8 +1,8 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include -#include +#include +#include #include int main(const int argc, char** argv) { diff --git a/src/ImuFilterChainNode.cc b/src/ImuFilterChainNode.cpp similarity index 85% rename from src/ImuFilterChainNode.cc rename to src/ImuFilterChainNode.cpp index bcf755d..57198d4 100644 --- a/src/ImuFilterChainNode.cc +++ b/src/ImuFilterChainNode.cpp @@ -1,7 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include int main(const int argc, char** argv) { diff --git a/src/JoyFilterChainNode.cc b/src/JoyFilterChainNode.cpp similarity index 85% rename from src/JoyFilterChainNode.cc rename to src/JoyFilterChainNode.cpp index c7cfef3..8ea85c3 100644 --- a/src/JoyFilterChainNode.cc +++ b/src/JoyFilterChainNode.cpp @@ -1,7 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include int main(const int argc, char** argv) { diff --git a/src/LaserScanFilterChainNode.cc b/src/LaserScanFilterChainNode.cpp similarity index 86% rename from src/LaserScanFilterChainNode.cc rename to src/LaserScanFilterChainNode.cpp index ef51c6f..87d8f2b 100644 --- a/src/LaserScanFilterChainNode.cc +++ b/src/LaserScanFilterChainNode.cpp @@ -1,7 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include int main(const int argc, char** argv) { diff --git a/src/MagneticFieldFilterChainNode.cc b/src/MagneticFieldFilterChainNode.cpp similarity index 87% rename from src/MagneticFieldFilterChainNode.cc rename to src/MagneticFieldFilterChainNode.cpp index 4fe3f09..76f1e42 100644 --- a/src/MagneticFieldFilterChainNode.cc +++ b/src/MagneticFieldFilterChainNode.cpp @@ -1,7 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include int main(const int argc, char** argv) { diff --git a/src/MultiEchoLaserScanFilterChainNode.cc b/src/MultiEchoLaserScanFilterChainNode.cpp similarity index 87% rename from src/MultiEchoLaserScanFilterChainNode.cc rename to src/MultiEchoLaserScanFilterChainNode.cpp index 4ab063b..242d51c 100644 --- a/src/MultiEchoLaserScanFilterChainNode.cc +++ b/src/MultiEchoLaserScanFilterChainNode.cpp @@ -1,7 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include int main(const int argc, char** argv) { diff --git a/src/NavSatFixFilterChainNode.cc b/src/NavSatFixFilterChainNode.cpp similarity index 86% rename from src/NavSatFixFilterChainNode.cc rename to src/NavSatFixFilterChainNode.cpp index f336789..d6af3b4 100644 --- a/src/NavSatFixFilterChainNode.cc +++ b/src/NavSatFixFilterChainNode.cpp @@ -1,7 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include int main(const int argc, char** argv) { diff --git a/src/PointCloud2FilterChainBase.cc b/src/PointCloud2FilterChainBase.cpp similarity index 92% rename from src/PointCloud2FilterChainBase.cc rename to src/PointCloud2FilterChainBase.cpp index c2b538d..46422aa 100644 --- a/src/PointCloud2FilterChainBase.cc +++ b/src/PointCloud2FilterChainBase.cpp @@ -4,8 +4,8 @@ #include #include #include -#include -#include +#include +#include namespace sensor_filters { void PointCloud2FilterChainBase::initFilters( diff --git a/src/PointCloud2FilterChainNode.cc b/src/PointCloud2FilterChainNode.cpp similarity index 76% rename from src/PointCloud2FilterChainNode.cc rename to src/PointCloud2FilterChainNode.cpp index 2302f5a..af203c2 100644 --- a/src/PointCloud2FilterChainNode.cc +++ b/src/PointCloud2FilterChainNode.cpp @@ -1,8 +1,8 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include -#include +#include +#include #include int main(const int argc, char** argv) { diff --git a/src/PointCloudFilterChainNode.cc b/src/PointCloudFilterChainNode.cpp similarity index 86% rename from src/PointCloudFilterChainNode.cc rename to src/PointCloudFilterChainNode.cpp index 038a6cb..e1e86ba 100644 --- a/src/PointCloudFilterChainNode.cc +++ b/src/PointCloudFilterChainNode.cpp @@ -1,7 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include int main(const int argc, char** argv) { diff --git a/src/RangeFilterChainNode.cc b/src/RangeFilterChainNode.cpp similarity index 85% rename from src/RangeFilterChainNode.cc rename to src/RangeFilterChainNode.cpp index 05a657c..e68a947 100644 --- a/src/RangeFilterChainNode.cc +++ b/src/RangeFilterChainNode.cpp @@ -1,7 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include int main(const int argc, char** argv) { diff --git a/src/RelativeHumidityFilterChainNode.cc b/src/RelativeHumidityFilterChainNode.cpp similarity index 87% rename from src/RelativeHumidityFilterChainNode.cc rename to src/RelativeHumidityFilterChainNode.cpp index 3eff349..53d5649 100644 --- a/src/RelativeHumidityFilterChainNode.cc +++ b/src/RelativeHumidityFilterChainNode.cpp @@ -1,7 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include int main(const int argc, char** argv) { diff --git a/src/TemperatureFilterChainNode.cc b/src/TemperatureFilterChainNode.cpp similarity index 86% rename from src/TemperatureFilterChainNode.cc rename to src/TemperatureFilterChainNode.cpp index 5e1e8ce..851c96e 100644 --- a/src/TemperatureFilterChainNode.cc +++ b/src/TemperatureFilterChainNode.cpp @@ -1,7 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague -#include +#include #include int main(const int argc, char** argv) { diff --git a/src/filters/ChangeHeaderFilter.cc b/src/filters/ChangeHeaderFilter.cc deleted file mode 100644 index 118b7d4..0000000 --- a/src/filters/ChangeHeaderFilter.cc +++ /dev/null @@ -1,103 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include - -#include -#include -#include - -#if ROS_VERSION_MINIMUM(1, 15, 0) -#include -#else -#include -#endif - -#include "include_all_msgs.hh" - -namespace sensor_filters -{ - -template -class ChangeHeader : public filters::FilterBase -{ -protected: - bool configure() override - { - { - std::string frameIdParam; - if (this->getParam("frame_id_prefix", frameIdParam)) - this->newFrameIdPrefix = frameIdParam; - - if (this->getParam("frame_id_suffix", frameIdParam)) - this->newFrameIdSuffix = frameIdParam; - - if (this->getParam("frame_id", frameIdParam)) - this->newFrameId = frameIdParam; - } - - { - uint32_t seqParam; - if (this->getParam("seq_relative", seqParam)) - this->newSeqRel = seqParam; - - if (this->getParam("seq", seqParam)) - this->newSeqAbs = seqParam; - } - - { - double stampParam; - if (this->getParam("stamp_relative", stampParam)) - this->newStampRel = ros::Duration(stampParam); - - if (this->getParam("stamp", stampParam)) - this->newStampAbs = ros::Time(stampParam); - } - - return true; - } - -public: - bool update(const T& data_in, T& data_out) override - { - data_out = data_in; - - if (this->newFrameIdPrefix.has_value()) - data_out.header.frame_id = this->newFrameIdPrefix.value() + data_out.header.frame_id; - - if (this->newFrameIdSuffix.has_value()) - data_out.header.frame_id += this->newFrameIdSuffix.value(); - - if (this->newFrameId.has_value()) - data_out.header.frame_id = this->newFrameId.value(); - - if (this->newSeqRel.has_value()) - data_out.header.seq += this->newSeqRel.value(); - - if (this->newSeqAbs.has_value()) - data_out.header.seq = this->newSeqAbs.value(); - - if (this->newStampRel.has_value()) - data_out.header.stamp += this->newStampRel.value(); - - if (this->newStampAbs.has_value()) - data_out.header.stamp = this->newStampAbs.value(); - - return true; - } - -private: - std::optional newFrameId; - std::optional newFrameIdPrefix; - std::optional newFrameIdSuffix; - - std::optional newSeqAbs; - std::optional newSeqRel; - - std::optional newStampAbs; - std::optional newStampRel; -}; - -} - -REGISTER_ALL_MSG_FILTER(sensor_filters::ChangeHeader) diff --git a/src/filters/ChangeHeaderFilter.cpp b/src/filters/ChangeHeaderFilter.cpp new file mode 100644 index 0000000..35920bf --- /dev/null +++ b/src/filters/ChangeHeaderFilter.cpp @@ -0,0 +1,97 @@ +// SPDX-License-Identifier: BSD-3-Clause +// SPDX-FileCopyrightText: Czech Technical University in Prague + +#include + +#include +#include +#include + +#if ROS_VERSION_MINIMUM(1, 15, 0) +#include +#else +#include +#endif + +#include "include_all_msgs.hpp" + +namespace sensor_filters { + template + class ChangeHeader : public filters::FilterBase { + protected: + bool configure() override { + { + std::string frameIdParam; + if (this->getParam("frame_id_prefix", frameIdParam)) + this->newFrameIdPrefix = frameIdParam; + + if (this->getParam("frame_id_suffix", frameIdParam)) + this->newFrameIdSuffix = frameIdParam; + + if (this->getParam("frame_id", frameIdParam)) + this->newFrameId = frameIdParam; + } + + { + uint32_t seqParam; + if (this->getParam("seq_relative", seqParam)) + this->newSeqRel = seqParam; + + if (this->getParam("seq", seqParam)) + this->newSeqAbs = seqParam; + } + + { + double stampParam; + if (this->getParam("stamp_relative", stampParam)) + this->newStampRel = ros::Duration(stampParam); + + if (this->getParam("stamp", stampParam)) + this->newStampAbs = ros::Time(stampParam); + } + + return true; + } + + public: + bool update(const T& data_in, T& data_out) override { + data_out = data_in; + + if (this->newFrameIdPrefix.has_value()) + data_out.header.frame_id = this->newFrameIdPrefix.value() + data_out.header.frame_id; + + if (this->newFrameIdSuffix.has_value()) + data_out.header.frame_id += this->newFrameIdSuffix.value(); + + if (this->newFrameId.has_value()) + data_out.header.frame_id = this->newFrameId.value(); + + if (this->newSeqRel.has_value()) + data_out.header.seq += this->newSeqRel.value(); + + if (this->newSeqAbs.has_value()) + data_out.header.seq = this->newSeqAbs.value(); + + if (this->newStampRel.has_value()) + data_out.header.stamp += this->newStampRel.value(); + + if (this->newStampAbs.has_value()) + data_out.header.stamp = this->newStampAbs.value(); + + return true; + } + + private: + std::optional newFrameId; + std::optional newFrameIdPrefix; + std::optional newFrameIdSuffix; + + std::optional newSeqAbs; + std::optional newSeqRel; + + std::optional newStampAbs; + std::optional newStampRel; + }; +} + +REGISTER_ALL_MSG_FILTER(sensor_filters::ChangeHeader) diff --git a/src/filters/include_all_msgs.hh b/src/filters/include_all_msgs.hpp similarity index 100% rename from src/filters/include_all_msgs.hh rename to src/filters/include_all_msgs.hpp From d4229aeeeb7592a10043befb73a640da5a776104 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 24 Feb 2026 14:44:33 -0500 Subject: [PATCH 04/23] generate filter chain nodes with cmake Signed-off-by: solonovamax --- CMakeLists.txt | 103 +++++++++++------- .../FilterChainNode.cpp.in | 5 +- cmake/GenerateFilterChainNode.cmake | 31 ++++++ src/CompressedImageFilterChainNode.cpp | 9 -- src/ImageFilterChainNode.cpp | 11 -- src/JoyFilterChainNode.cpp | 9 -- src/LaserScanFilterChainNode.cpp | 9 -- src/MagneticFieldFilterChainNode.cpp | 9 -- src/MultiEchoLaserScanFilterChainNode.cpp | 9 -- src/NavSatFixFilterChainNode.cpp | 9 -- src/PointCloud2FilterChainNode.cpp | 10 -- src/PointCloudFilterChainNode.cpp | 9 -- src/RangeFilterChainNode.cpp | 9 -- src/RelativeHumidityFilterChainNode.cpp | 9 -- src/TemperatureFilterChainNode.cpp | 9 -- 15 files changed, 98 insertions(+), 152 deletions(-) rename src/ImuFilterChainNode.cpp => cmake/FilterChainNode.cpp.in (60%) create mode 100644 cmake/GenerateFilterChainNode.cmake delete mode 100644 src/CompressedImageFilterChainNode.cpp delete mode 100644 src/ImageFilterChainNode.cpp delete mode 100644 src/JoyFilterChainNode.cpp delete mode 100644 src/LaserScanFilterChainNode.cpp delete mode 100644 src/MagneticFieldFilterChainNode.cpp delete mode 100644 src/MultiEchoLaserScanFilterChainNode.cpp delete mode 100644 src/NavSatFixFilterChainNode.cpp delete mode 100644 src/PointCloud2FilterChainNode.cpp delete mode 100644 src/PointCloudFilterChainNode.cpp delete mode 100644 src/RangeFilterChainNode.cpp delete mode 100644 src/RelativeHumidityFilterChainNode.cpp delete mode 100644 src/TemperatureFilterChainNode.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 52b03b8..e7716be 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -29,53 +29,78 @@ endforeach () include_directories(include include/${PROJECT_NAME}) -set(types - CompressedImage - Image - Imu - Joy - LaserScan - MultiEchoLaserScan - MagneticField - NavSatFix - PointCloud - PointCloud2 - Range - RelativeHumidity - Temperature -) - -foreach (type IN LISTS types) - string(TOLOWER "${type}" type_lower) - - set(node_name "${type_lower}_filter_chain") - - list(APPEND NODE_TARGETS ${node_name}) - - # add_library(${node_name} src/${type}FilterChainNodelet.cpp) - # #target_link_libraries(${nodelet_name} ${DEPENDENCIES}) - # ament_target_dependencies(${node_name} ${DEPENDENCIES}) +function(add_filter_chain_node TARGET_NAME FILENAME) + list(APPEND NODE_TARGETS ${TARGET_NAME}) - add_executable(${node_name} src/${type}FilterChainNode.cpp) - #target_link_libraries(${node_name} ${DEPENDENCIES}) - ament_target_dependencies(${node_name} ${DEPENDENCIES}) + add_executable(${TARGET_NAME} "${FILENAME}") + #target_link_libraries(${TARGET_NAME} ${DEPENDENCIES}) + ament_target_dependencies(${TARGET_NAME} ${DEPENDENCIES}) - # install(TARGETS ${node_name} - # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - # ) + #install(TARGETS ${TARGET_NAME} + # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + #) - install(TARGETS ${node_name} + install(TARGETS ${TARGET_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION lib ) -endforeach () +endfunction() + +function(generate_filter_chain_source NODE_NAME) + set(oneValueArgs HEADER_NAME MESSAGE_TYPE BASE_FILTER) + set(multiValueArgs SOURCES) + cmake_parse_arguments(PARSE_ARGV 0 arg + "" "${oneValueArgs}" "${multiValueArgs}" + ) + + set(BASE_FILTER "${arg_BASE_FILTER}") + set(HEADER_NAME "${arg_HEADER_NAME}") + set(MESSAGE_TYPE "${arg_MESSAGE_TYPE}") + set(SOURCES "${arg_SOURCES}") + + set(NODE_NAME "${NODE_NAME}_filter_chain") + + set(FILE_NAME "${MESSAGE_TYPE}FilterChain.cpp") + + set(OUTPUT_FILE "${PROJECT_BINARY_DIR}/${FILE_NAME}") + + add_custom_command( + OUTPUT "${OUTPUT_FILE}" + COMMAND ${CMAKE_COMMAND} + -D "PROJECT_SOURCE_DIR=${PROJECT_SOURCE_DIR}" + -D "MESSAGE_TYPE=${MESSAGE_TYPE}" + -D "HEADER_NAME=${HEADER_NAME}" + -D "BASE_FILTER=${BASE_FILTER}" + -D "NODE_NAME=${NODE_NAME}" + -D "OUTPUT_FILE=${OUTPUT_FILE}" + -P "${CMAKE_SOURCE_DIR}/cmake/GenerateFilterChainNode.cmake" + DEPENDS + "${CMAKE_CURRENT_SOURCE_DIR}/cmake/FilterChainNode.cpp.in" + "${CMAKE_SOURCE_DIR}/cmake/GenerateFilterChainNode.cmake" + VERBATIM + ) -# Additional sources for the targets that use custom transport -#target_sources(image_filter_chain_nodelet PRIVATE src/ImageFilterChainBase.cpp) -target_sources(image_filter_chain PRIVATE src/ImageFilterChainBase.cpp) -#target_sources(pointcloud2_filter_chain_nodelet PRIVATE src/PointCloud2FilterChainBase.cpp) -target_sources(pointcloud2_filter_chain PRIVATE src/PointCloud2FilterChainBase.cpp) + add_filter_chain_node(${NODE_NAME} "${OUTPUT_FILE}") + + if (SOURCES) + target_sources(${NODE_NAME} PRIVATE ${SOURCES}) + endif () +endfunction() + +generate_filter_chain_source("compressed_image" HEADER_NAME "compressed_image" MESSAGE_TYPE "CompressedImage") +generate_filter_chain_source("image" HEADER_NAME "image" MESSAGE_TYPE "Image" BASE_FILTER "ImageFilterChainBase" SOURCES src/ImageFilterChainBase.cpp) +generate_filter_chain_source("imu" HEADER_NAME "imu" MESSAGE_TYPE "Imu") +generate_filter_chain_source("joy" HEADER_NAME "joy" MESSAGE_TYPE "Joy") +generate_filter_chain_source("scan" HEADER_NAME "laser_scan" MESSAGE_TYPE "LaserScan") +generate_filter_chain_source("magnetic_field" HEADER_NAME "magnetic_field" MESSAGE_TYPE "MagneticField") +generate_filter_chain_source("multi_echo_scan" HEADER_NAME "multi_echo_laser_scan" MESSAGE_TYPE "MultiEchoLaserScan") +generate_filter_chain_source("navsat_fix" HEADER_NAME "nav_sat_fix" MESSAGE_TYPE "NavSatFix") +generate_filter_chain_source("pointcloud" HEADER_NAME "point_cloud" MESSAGE_TYPE "PointCloud") +generate_filter_chain_source("pointcloud2" HEADER_NAME "point_cloud2" MESSAGE_TYPE "PointCloud2" BASE_FILTER "PointCloud2FilterChainBase" SOURCES src/PointCloud2FilterChainBase.cpp) +generate_filter_chain_source("range" HEADER_NAME "range" MESSAGE_TYPE "Range") +generate_filter_chain_source("relative_humidity" HEADER_NAME "relative_humidity" MESSAGE_TYPE "RelativeHumidity") +generate_filter_chain_source("temperature" HEADER_NAME "temperature" MESSAGE_TYPE "Temperature") # TODO 2026-02-23 (solonovamax): finish this # diff --git a/src/ImuFilterChainNode.cpp b/cmake/FilterChainNode.cpp.in similarity index 60% rename from src/ImuFilterChainNode.cpp rename to cmake/FilterChainNode.cpp.in index 57198d4..823bc47 100644 --- a/src/ImuFilterChainNode.cpp +++ b/cmake/FilterChainNode.cpp.in @@ -2,8 +2,9 @@ // SPDX-FileCopyrightText: Czech Technical University in Prague #include -#include +@BASE_INCLUDE@ +#include <@MESSAGE_HEADER@> int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("imu_filter_chain", argc, argv); + sensor_filters::spinFilterChain<@TEMPLATE_ARGS@>("@NODE_NAME@", argc, argv); } diff --git a/cmake/GenerateFilterChainNode.cmake b/cmake/GenerateFilterChainNode.cmake new file mode 100644 index 0000000..82842b9 --- /dev/null +++ b/cmake/GenerateFilterChainNode.cmake @@ -0,0 +1,31 @@ +# ${MESSAGE_TYPE} = sensor_msgs::msg::CompressedImage +# ${NODE_NAME} = image_filter_chain + +#string(REGEX REPLACE "(_|^)([a-zA-Z])" "\\U$1\\E" FILE_NAME ${NODE_NAME}) +#string(APPEND FILE_NAME "FilterChainNode.cpp") +#string(REPLACE "::" "/" MESSAGE_HEADER ${MESSAGE_TYPE}) +#string(APPEND MESSAGE_HEADER ".hpp") + +set(MESSAGE_TYPE "sensor_msgs::msg::${MESSAGE_TYPE}") +set(MESSAGE_HEADER "sensor_msgs/msg/${HEADER_NAME}.hpp") + +message(MESSAGE_TYPE="${MESSAGE_TYPE}") +message(HEADER_NAME="${HEADER_NAME}") +message(MESSAGE_HEADER="${MESSAGE_HEADER}") +if (BASE_FILTER) + set(TEMPLATE_ARGS "${MESSAGE_TYPE}, sensor_filters::${BASE_FILTER}") + # string(REPLACE "::" "/" "${BASE_FILTER}") + set(BASE_INCLUDE "#include ") +else () + set(TEMPLATE_ARGS "${MESSAGE_TYPE}") + set(BASE_INCLUDE "") +endif () +message(NODE_NAME="${NODE_NAME}") +message(BASE_FILTER="${BASE_FILTER}") +message(TEMPLATE_ARGS="${TEMPLATE_ARGS}") + +# Configure the header file +configure_file(${PROJECT_SOURCE_DIR}/cmake/FilterChainNode.cpp.in ${OUTPUT_FILE} @ONLY) + +file(READ ${OUTPUT_FILE} CONTENTS) +message(CONTENTS=${CONTENTS}) diff --git a/src/CompressedImageFilterChainNode.cpp b/src/CompressedImageFilterChainNode.cpp deleted file mode 100644 index bf63134..0000000 --- a/src/CompressedImageFilterChainNode.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("image_filter_chain", argc, argv); -} diff --git a/src/ImageFilterChainNode.cpp b/src/ImageFilterChainNode.cpp deleted file mode 100644 index a1015bf..0000000 --- a/src/ImageFilterChainNode.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain( - "image_filter_chain", argc, argv); -} diff --git a/src/JoyFilterChainNode.cpp b/src/JoyFilterChainNode.cpp deleted file mode 100644 index 8ea85c3..0000000 --- a/src/JoyFilterChainNode.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("joy_filter_chain", argc, argv); -} diff --git a/src/LaserScanFilterChainNode.cpp b/src/LaserScanFilterChainNode.cpp deleted file mode 100644 index 87d8f2b..0000000 --- a/src/LaserScanFilterChainNode.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("scan_filter_chain", argc, argv); -} diff --git a/src/MagneticFieldFilterChainNode.cpp b/src/MagneticFieldFilterChainNode.cpp deleted file mode 100644 index 76f1e42..0000000 --- a/src/MagneticFieldFilterChainNode.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("magnetic_field_filter_chain", argc, argv); -} diff --git a/src/MultiEchoLaserScanFilterChainNode.cpp b/src/MultiEchoLaserScanFilterChainNode.cpp deleted file mode 100644 index 242d51c..0000000 --- a/src/MultiEchoLaserScanFilterChainNode.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("scan_filter_chain", argc, argv); -} diff --git a/src/NavSatFixFilterChainNode.cpp b/src/NavSatFixFilterChainNode.cpp deleted file mode 100644 index d6af3b4..0000000 --- a/src/NavSatFixFilterChainNode.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("nav_sat_fix_filter_chain", argc, argv); -} diff --git a/src/PointCloud2FilterChainNode.cpp b/src/PointCloud2FilterChainNode.cpp deleted file mode 100644 index af203c2..0000000 --- a/src/PointCloud2FilterChainNode.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("cloud_filter_chain", argc, argv); -} diff --git a/src/PointCloudFilterChainNode.cpp b/src/PointCloudFilterChainNode.cpp deleted file mode 100644 index e1e86ba..0000000 --- a/src/PointCloudFilterChainNode.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("cloud_filter_chain", argc, argv); -} diff --git a/src/RangeFilterChainNode.cpp b/src/RangeFilterChainNode.cpp deleted file mode 100644 index e68a947..0000000 --- a/src/RangeFilterChainNode.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("range_filter_chain", argc, argv); -} diff --git a/src/RelativeHumidityFilterChainNode.cpp b/src/RelativeHumidityFilterChainNode.cpp deleted file mode 100644 index 53d5649..0000000 --- a/src/RelativeHumidityFilterChainNode.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("humidity_filter_chain", argc, argv); -} diff --git a/src/TemperatureFilterChainNode.cpp b/src/TemperatureFilterChainNode.cpp deleted file mode 100644 index 851c96e..0000000 --- a/src/TemperatureFilterChainNode.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include - -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain("temperature_filter_chain", argc, argv); -} From 3213d14f07f9704381f18151194302cdc0260855 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 24 Feb 2026 14:47:36 -0500 Subject: [PATCH 05/23] use correct name for node Signed-off-by: solonovamax --- include/sensor_filters/FilterChainNode.hpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/include/sensor_filters/FilterChainNode.hpp b/include/sensor_filters/FilterChainNode.hpp index b19e7c9..868c3f9 100644 --- a/include/sensor_filters/FilterChainNode.hpp +++ b/include/sensor_filters/FilterChainNode.hpp @@ -15,18 +15,19 @@ namespace sensor_filters { template > class FilterChainNode : public rclcpp::Node, public Base { public: - explicit FilterChainNode() : Base(), Node("") {} + explicit FilterChainNode(const std::string& name) : Node(name), Base() {} }; template > - void spinFilterChain(const std::string& filterChainNamespace, const int argc, char** argv) { + void spinFilterChain(const std::string& name, const int argc, char** argv) { rclcpp::init(argc, argv); - const auto node = std::make_shared>(); + const auto node = std::make_shared>(name); node->initFilters( - filterChainNamespace, node, false, + name, node, false, node->declare_parameter("input_queue_size", 10), - node->declare_parameter("output_queue_size", 10)); + node->declare_parameter("output_queue_size", 10) + ); rclcpp::spin(node); } } From c52f1235776c98191cd27ce47c1228bea3a0a11e Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 24 Feb 2026 16:12:18 -0500 Subject: [PATCH 06/23] make nodes composable Signed-off-by: solonovamax --- CMakeLists.txt | 24 +++++++++++++-------- cmake/FilterChainNode.cpp.in | 12 +++++++++-- include/sensor_filters/FilterChainNode.hpp | 25 +++++++++++++++------- 3 files changed, 42 insertions(+), 19 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e7716be..0f54c80 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,13 +12,15 @@ if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif () -set(DEPENDENCIES robot_body_filter_msgs - backward_ros +set(DEPENDENCIES + robot_body_filter_msgs + rclcpp + rclcpp_components filters + sensor_msgs image_transport point_cloud_transport - rclcpp - sensor_msgs + backward_ros ) find_package(ament_cmake REQUIRED) @@ -29,12 +31,14 @@ endforeach () include_directories(include include/${PROJECT_NAME}) -function(add_filter_chain_node TARGET_NAME FILENAME) +function(add_filter_chain_node TARGET_NAME CLASS_NAME FILENAME) list(APPEND NODE_TARGETS ${TARGET_NAME}) - add_executable(${TARGET_NAME} "${FILENAME}") + add_library("${TARGET_NAME}_component" SHARED "${FILENAME}") + rclcpp_components_register_node(${TARGET_NAME}_component PLUGIN "sensor_filters::${CLASS_NAME}" EXECUTABLE ${TARGET_NAME}) + #add_executable(${TARGET_NAME} "${FILENAME}") #target_link_libraries(${TARGET_NAME} ${DEPENDENCIES}) - ament_target_dependencies(${TARGET_NAME} ${DEPENDENCIES}) + ament_target_dependencies("${TARGET_NAME}_component" ${DEPENDENCIES}) #install(TARGETS ${TARGET_NAME} # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} @@ -61,6 +65,7 @@ function(generate_filter_chain_source NODE_NAME) set(NODE_NAME "${NODE_NAME}_filter_chain") + set(CLASS_NAME "${MESSAGE_TYPE}FilterChainNode") set(FILE_NAME "${MESSAGE_TYPE}FilterChain.cpp") set(OUTPUT_FILE "${PROJECT_BINARY_DIR}/${FILE_NAME}") @@ -72,6 +77,7 @@ function(generate_filter_chain_source NODE_NAME) -D "MESSAGE_TYPE=${MESSAGE_TYPE}" -D "HEADER_NAME=${HEADER_NAME}" -D "BASE_FILTER=${BASE_FILTER}" + -D "CLASS_NAME=${CLASS_NAME}" -D "NODE_NAME=${NODE_NAME}" -D "OUTPUT_FILE=${OUTPUT_FILE}" -P "${CMAKE_SOURCE_DIR}/cmake/GenerateFilterChainNode.cmake" @@ -81,10 +87,10 @@ function(generate_filter_chain_source NODE_NAME) VERBATIM ) - add_filter_chain_node(${NODE_NAME} "${OUTPUT_FILE}") + add_filter_chain_node(${NODE_NAME} "${CLASS_NAME}" "${OUTPUT_FILE}") if (SOURCES) - target_sources(${NODE_NAME} PRIVATE ${SOURCES}) + target_sources(${NODE_NAME}_component PRIVATE ${SOURCES}) endif () endfunction() diff --git a/cmake/FilterChainNode.cpp.in b/cmake/FilterChainNode.cpp.in index 823bc47..37d1f8e 100644 --- a/cmake/FilterChainNode.cpp.in +++ b/cmake/FilterChainNode.cpp.in @@ -5,6 +5,14 @@ @BASE_INCLUDE@ #include <@MESSAGE_HEADER@> -int main(const int argc, char** argv) { - sensor_filters::spinFilterChain<@TEMPLATE_ARGS@>("@NODE_NAME@", argc, argv); +namespace sensor_filters { + class @CLASS_NAME@ : public FilterChainNode<@TEMPLATE_ARGS@> { + public: + @CLASS_NAME@(const rclcpp::NodeOptions& options) : FilterChainNode("@NODE_NAME@", options) {} + + explicit @CLASS_NAME@(): FilterChainNode("@NODE_NAME@") {} + }; } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(sensor_filters::@CLASS_NAME@) diff --git a/include/sensor_filters/FilterChainNode.hpp b/include/sensor_filters/FilterChainNode.hpp index 868c3f9..16141be 100644 --- a/include/sensor_filters/FilterChainNode.hpp +++ b/include/sensor_filters/FilterChainNode.hpp @@ -15,19 +15,28 @@ namespace sensor_filters { template > class FilterChainNode : public rclcpp::Node, public Base { public: - explicit FilterChainNode(const std::string& name) : Node(name), Base() {} + explicit FilterChainNode(const std::string& name, const rclcpp::NodeOptions& options) : Node(name, options), Base() { + this->initFilters( + name, this->node, false, + this->declare_parameter("input_queue_size", 10), + this->declare_parameter("output_queue_size", 10) + ); + } + + explicit FilterChainNode(const std::string& name) : Node(name), Base() { + this->initFilters( + name, this->node, false, + this->declare_parameter("input_queue_size", 10), + this->declare_parameter("output_queue_size", 10) + ); + } }; template > - void spinFilterChain(const std::string& name, const int argc, char** argv) { + void spinFilterChain(const int argc, char** argv) { rclcpp::init(argc, argv); - const auto node = std::make_shared>(name); - node->initFilters( - name, node, false, - node->declare_parameter("input_queue_size", 10), - node->declare_parameter("output_queue_size", 10) - ); + const auto node = std::make_shared>(); rclcpp::spin(node); } } From 615f6ab9ba0807b4790d2ccbb64e65f98655c7c8 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 24 Feb 2026 16:13:34 -0500 Subject: [PATCH 07/23] cleanup GenerateFilterChainNode.cmake Signed-off-by: solonovamax --- cmake/GenerateFilterChainNode.cmake | 19 ------------------- 1 file changed, 19 deletions(-) diff --git a/cmake/GenerateFilterChainNode.cmake b/cmake/GenerateFilterChainNode.cmake index 82842b9..18e97b5 100644 --- a/cmake/GenerateFilterChainNode.cmake +++ b/cmake/GenerateFilterChainNode.cmake @@ -1,31 +1,12 @@ -# ${MESSAGE_TYPE} = sensor_msgs::msg::CompressedImage -# ${NODE_NAME} = image_filter_chain - -#string(REGEX REPLACE "(_|^)([a-zA-Z])" "\\U$1\\E" FILE_NAME ${NODE_NAME}) -#string(APPEND FILE_NAME "FilterChainNode.cpp") -#string(REPLACE "::" "/" MESSAGE_HEADER ${MESSAGE_TYPE}) -#string(APPEND MESSAGE_HEADER ".hpp") - set(MESSAGE_TYPE "sensor_msgs::msg::${MESSAGE_TYPE}") set(MESSAGE_HEADER "sensor_msgs/msg/${HEADER_NAME}.hpp") -message(MESSAGE_TYPE="${MESSAGE_TYPE}") -message(HEADER_NAME="${HEADER_NAME}") -message(MESSAGE_HEADER="${MESSAGE_HEADER}") if (BASE_FILTER) set(TEMPLATE_ARGS "${MESSAGE_TYPE}, sensor_filters::${BASE_FILTER}") - # string(REPLACE "::" "/" "${BASE_FILTER}") set(BASE_INCLUDE "#include ") else () set(TEMPLATE_ARGS "${MESSAGE_TYPE}") set(BASE_INCLUDE "") endif () -message(NODE_NAME="${NODE_NAME}") -message(BASE_FILTER="${BASE_FILTER}") -message(TEMPLATE_ARGS="${TEMPLATE_ARGS}") -# Configure the header file configure_file(${PROJECT_SOURCE_DIR}/cmake/FilterChainNode.cpp.in ${OUTPUT_FILE} @ONLY) - -file(READ ${OUTPUT_FILE} CONTENTS) -message(CONTENTS=${CONTENTS}) From 6a708f564b896089525bb2815cded0d5d7533c0e Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 24 Feb 2026 16:20:31 -0500 Subject: [PATCH 08/23] add deprecation note for non-composable constructors I'm leaving them there for now in case for some reason something comes up in the future where someone can't use a composable node for whatever reason Signed-off-by: solonovamax --- include/sensor_filters/FilterChainNode.hpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/include/sensor_filters/FilterChainNode.hpp b/include/sensor_filters/FilterChainNode.hpp index 16141be..b3a139d 100644 --- a/include/sensor_filters/FilterChainNode.hpp +++ b/include/sensor_filters/FilterChainNode.hpp @@ -23,7 +23,8 @@ namespace sensor_filters { ); } - explicit FilterChainNode(const std::string& name) : Node(name), Base() { + //! use a composable node instead + [[deprecated]] explicit FilterChainNode(const std::string& name) : Node(name), Base() { this->initFilters( name, this->node, false, this->declare_parameter("input_queue_size", 10), @@ -32,11 +33,11 @@ namespace sensor_filters { } }; - + //! this method is deprecated, and instead a composable node should be used template > - void spinFilterChain(const int argc, char** argv) { + [[deprecated]] void spinFilterChain(const std::string& name, const int argc, char** argv) { rclcpp::init(argc, argv); - const auto node = std::make_shared>(); + const auto node = std::make_shared>(name); rclcpp::spin(node); } } From a1ce80ab95bef327d0b49a6ed035b62f372784e3 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 24 Feb 2026 17:19:04 -0500 Subject: [PATCH 09/23] how did this accidentally get in there Signed-off-by: solonovamax --- CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 0f54c80..482269f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -13,7 +13,6 @@ if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") endif () set(DEPENDENCIES - robot_body_filter_msgs rclcpp rclcpp_components filters From df62f549280171411b713aa2277436ec663ea3de Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 24 Feb 2026 17:20:34 -0500 Subject: [PATCH 10/23] port ChangeHeaderFilter to ros2 Signed-off-by: solonovamax --- CMakeLists.txt | 58 +++++++++++++----------------- src/filters/ChangeHeaderFilter.cpp | 35 ++++-------------- src/filters/include_all_msgs.hpp | 55 ++++++++++++++-------------- 3 files changed, 58 insertions(+), 90 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 482269f..f9445da 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -46,7 +46,7 @@ function(add_filter_chain_node TARGET_NAME CLASS_NAME FILENAME) install(TARGETS ${TARGET_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib - RUNTIME DESTINATION lib + RUNTIME DESTINATION bin ) endfunction() @@ -107,39 +107,31 @@ generate_filter_chain_source("range" HEADER_NAME "range" MESSAGE_TYPE "Range") generate_filter_chain_source("relative_humidity" HEADER_NAME "relative_humidity" MESSAGE_TYPE "RelativeHumidity") generate_filter_chain_source("temperature" HEADER_NAME "temperature" MESSAGE_TYPE "Temperature") -# TODO 2026-02-23 (solonovamax): finish this -# -#set(filters -# ChangeHeaderFilter -#) -# -#foreach (filter IN LISTS filters) -# add_library(${filter} src/filters/${filter}.cpp) -# add_dependencies(${filter} ${catkin_EXPORTED_TARGETS}) -# target_link_libraries(${filter} ${catkin_LIBRARIES}) -# install(TARGETS ${filter} -# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} -# ) -# install(FILES -# ${filter}.xml -# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -# ) -#endforeach () +set(filters + ChangeHeaderFilter +) + +foreach (filter IN LISTS filters) + list(APPEND FILTER_LIBRARIES ${filter}) + + add_library(${filter} src/filters/${filter}.cpp) + ament_target_dependencies(${filter} ${DEPENDENCIES}) + # target_link_libraries(${filter} ${catkin_LIBRARIES}) + pluginlib_export_plugin_description_file(filters ${filter}.xml) +endforeach () + +install(TARGETS ${FILTER_LIBRARIES} + EXPORT export_${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) install( DIRECTORY include/ DESTINATION include ) -#install(TARGETS ${NODE_TARGETS} -# EXPORT export_${PROJECT_NAME} -# RUNTIME DESTINATION bin -# ARCHIVE DESTINATION lib -# LIBRARY DESTINATION lib -#) - #if (CATKIN_ENABLE_TESTING) # find_package(roslint REQUIRED) # @@ -173,10 +165,8 @@ install( # roslint_add_test() #endif () -#ament_export_include_directories(include include/${PROJECT_NAME}) -#ament_export_dependencies(${DEPENDENCIES}) -#ament_export_libraries(${PROJECT_NAME} ) -#ament_export_targets( -# export_${PROJECT_NAME} -#) +ament_export_include_directories(include include/${PROJECT_NAME}) +ament_export_dependencies(${DEPENDENCIES}) +ament_export_libraries(${FILTER_LIBRARIES}) +ament_export_targets(export_${PROJECT_NAME}) ament_package() diff --git a/src/filters/ChangeHeaderFilter.cpp b/src/filters/ChangeHeaderFilter.cpp index 35920bf..148e596 100644 --- a/src/filters/ChangeHeaderFilter.cpp +++ b/src/filters/ChangeHeaderFilter.cpp @@ -2,16 +2,8 @@ // SPDX-FileCopyrightText: Czech Technical University in Prague #include - -#include -#include -#include - -#if ROS_VERSION_MINIMUM(1, 15, 0) #include -#else -#include -#endif +#include #include "include_all_msgs.hpp" @@ -32,22 +24,13 @@ namespace sensor_filters { this->newFrameId = frameIdParam; } - { - uint32_t seqParam; - if (this->getParam("seq_relative", seqParam)) - this->newSeqRel = seqParam; - - if (this->getParam("seq", seqParam)) - this->newSeqAbs = seqParam; - } - { double stampParam; if (this->getParam("stamp_relative", stampParam)) - this->newStampRel = ros::Duration(stampParam); + this->newStampRel = rclcpp::Duration::from_seconds(stampParam); if (this->getParam("stamp", stampParam)) - this->newStampAbs = ros::Time(stampParam); + this->newStampAbs = rclcpp::Time(stampParam); } return true; @@ -66,14 +49,8 @@ namespace sensor_filters { if (this->newFrameId.has_value()) data_out.header.frame_id = this->newFrameId.value(); - if (this->newSeqRel.has_value()) - data_out.header.seq += this->newSeqRel.value(); - - if (this->newSeqAbs.has_value()) - data_out.header.seq = this->newSeqAbs.value(); - if (this->newStampRel.has_value()) - data_out.header.stamp += this->newStampRel.value(); + data_out.header.stamp = rclcpp::Time(data_out.header.stamp) + this->newStampRel.value(); if (this->newStampAbs.has_value()) data_out.header.stamp = this->newStampAbs.value(); @@ -89,8 +66,8 @@ namespace sensor_filters { std::optional newSeqAbs; std::optional newSeqRel; - std::optional newStampAbs; - std::optional newStampRel; + std::optional newStampAbs; + std::optional newStampRel; }; } diff --git a/src/filters/include_all_msgs.hpp b/src/filters/include_all_msgs.hpp index b0cec60..e127870 100644 --- a/src/filters/include_all_msgs.hpp +++ b/src/filters/include_all_msgs.hpp @@ -8,32 +8,33 @@ #pragma once -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #define REGISTER_ALL_MSG_FILTER(filter) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ +PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) From 86921dabbebe09a33b5e18376a7351bed100a4f4 Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Wed, 25 Feb 2026 10:05:05 +0100 Subject: [PATCH 11/23] Added CI for ROS 2 --- .github/workflows/ci-ros2.yaml | 66 ++++++++++++++++++++++++++++++++++ 1 file changed, 66 insertions(+) create mode 100644 .github/workflows/ci-ros2.yaml diff --git a/.github/workflows/ci-ros2.yaml b/.github/workflows/ci-ros2.yaml new file mode 100644 index 0000000..6805df2 --- /dev/null +++ b/.github/workflows/ci-ros2.yaml @@ -0,0 +1,66 @@ +# SPDX-License-Identifier: BSD-3-Clause +# SPDX-FileCopyrightText: Czech Technical University in Prague + +# This config uses industrial_ci (https://github.com/ros-industrial/industrial_ci.git). +# For troubleshooting, see readme (https://github.com/ros-industrial/industrial_ci/blob/master/README.rst) + +name: CI + +# This determines when this workflow is run +on: + push: + branches: [ros2] + pull_request: + branches: [ros2] + workflow_dispatch: {} + +jobs: + industrial_ci: + strategy: + fail-fast: false + matrix: + env: + - {ROS_DISTRO: humble, ROS_REPO: testing, DOCKER_IMAGE: "ghcr.io/sloretz/ros:humble-perception", ALLOW_FAIL: yes} + - {ROS_DISTRO: jazzy, ROS_REPO: testing, DOCKER_IMAGE: "ghcr.io/sloretz/ros:jazzy-perception", ALLOW_FAIL: no} + - {ROS_DISTRO: kilted, ROS_REPO: testing, DOCKER_IMAGE: "ghcr.io/sloretz/ros:kilted-perception", ALLOW_FAIL: no} + - {ROS_DISTRO: rolling, ROS_REPO: testing, DOCKER_IMAGE: "ghcr.io/sloretz/ros:rolling-perception", ALLOW_FAIL: yes} + os: ["ubuntu-24.04", "ubuntu-24.04-arm"] + name: "${{ matrix.env.ROS_DISTRO }}-${{ matrix.os }}" + env: + CCACHE_DIR: &ccache ${{ github.workspace }}/.ccache # Directory for ccache (and how we enable ccache in industrial_ci) + VERBOSE_OUTPUT: &verbose true + runs-on: &runs-on ${{ matrix.os }} + steps: &steps + - uses: actions/checkout@v4 + # This step will fetch/store the directory used by ccache before/after the ci run + - name: Cache ccache + uses: rhaschke/cache@main + continue-on-error: ${{ matrix.env.ALLOW_FAIL }} + with: + path: ${{ env.CCACHE_DIR }} + key: ccache-${{ matrix.os }}-${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }}-${{ github.sha }}-${{ github.run_id }} + restore-keys: | + ccache-${{ matrix.os }}-${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }}-${{ github.sha }} + ccache-${{ matrix.os }}-${{ matrix.env.ROS_DISTRO }} + env: + GHA_CACHE_SAVE: always + # Run industrial_ci + - uses: 'ros-industrial/industrial_ci@master' + env: ${{ matrix.env }} + # We also do a best effort test with GCC 11 (which is on RHEL 9 on ROS buildfarm) + industrial_ci_gcc_11: + strategy: + fail-fast: false + matrix: + env: + - { ROS_DISTRO: kilted, ROS_REPO: testing, DOCKER_IMAGE: "ghcr.io/sloretz/ros:kilted-perception", ALLOW_FAIL: yes } + os: [ "ubuntu-24.04", "ubuntu-24.04-arm" ] + name: "${{ matrix.env.ROS_DISTRO }}-${{ matrix.os }}-gcc11" + env: + CCACHE_DIR: *ccache + VERBOSE_OUTPUT: *verbose + ADDITIONAL_DEBS: "g++-11" + CC: "gcc-11" + CXX: "g++-11" + runs-on: *runs-on + steps: *steps \ No newline at end of file From fe9d6b7274ddcaddd5ef46b58ec34513cd8fd187 Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Wed, 25 Feb 2026 10:09:40 +0100 Subject: [PATCH 12/23] Converted package.xml to ROS 2 --- package.xml | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/package.xml b/package.xml index 6a14b41..7099c53 100644 --- a/package.xml +++ b/package.xml @@ -15,26 +15,25 @@ SPDX-FileCopyrightText: Czech Technical University in Prague https://github.com/ctu-vras/sensor_filters - catkin + ament_cmake filters - nodelet - roscpp + rclcpp + rclcpp_components sensor_msgs + backward_ros image_transport point_cloud_transport + backward_ros image_transport point_cloud_transport - python-catkin-lint - python3-catkin-lint - roslint + - - + ament_cmake From 4ac012f010736b7d1d6a435c22fa18c07c011a17 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 17 Mar 2026 12:41:24 -0400 Subject: [PATCH 13/23] Add lifecycle nodes The current implementation offers both a lifecycle node, as well as a non-lifecycle node. The reason for doing this, is because the lifecycle node requires additional code to start it. So, a non-lifecycle node is offered for simplicity. Lifecycle nodes are currently not offered for the image & pointcloud2 filter types. Signed-off-by: solonovamax --- CMakeLists.txt | 43 +++- cmake/GenerateFilterChainNode.cmake | 6 +- cmake/LifecycleFilterChainNode.cpp.in | 18 ++ include/sensor_filters/FilterChainBase.hpp | 100 ++++---- include/sensor_filters/FilterChainNode.hpp | 223 +++++++++++++++++- .../sensor_filters/ImageFilterChainBase.hpp | 43 ---- .../PointCloud2FilterChainBase.hpp | 43 ---- package.xml | 2 + src/ImageFilterChainBase.cpp | 40 ---- src/ImageFilterChainNode.cpp | 47 ++++ src/PointCloud2FilterChainBase.cpp | 38 --- src/PointCloud2FilterChainNode.cpp | 47 ++++ 12 files changed, 413 insertions(+), 237 deletions(-) create mode 100644 cmake/LifecycleFilterChainNode.cpp.in delete mode 100644 include/sensor_filters/ImageFilterChainBase.hpp delete mode 100644 include/sensor_filters/PointCloud2FilterChainBase.hpp delete mode 100644 src/ImageFilterChainBase.cpp create mode 100644 src/ImageFilterChainNode.cpp delete mode 100644 src/PointCloud2FilterChainBase.cpp create mode 100644 src/PointCloud2FilterChainNode.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index f9445da..b941f94 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -15,6 +15,8 @@ endif () set(DEPENDENCIES rclcpp rclcpp_components + rclcpp_lifecycle + lifecycle_msgs filters sensor_msgs image_transport @@ -51,10 +53,11 @@ function(add_filter_chain_node TARGET_NAME CLASS_NAME FILENAME) endfunction() function(generate_filter_chain_source NODE_NAME) + set(options NO_LIFECYCLE) set(oneValueArgs HEADER_NAME MESSAGE_TYPE BASE_FILTER) set(multiValueArgs SOURCES) cmake_parse_arguments(PARSE_ARGV 0 arg - "" "${oneValueArgs}" "${multiValueArgs}" + "${options}" "${oneValueArgs}" "${multiValueArgs}" ) set(BASE_FILTER "${arg_BASE_FILTER}") @@ -79,6 +82,7 @@ function(generate_filter_chain_source NODE_NAME) -D "CLASS_NAME=${CLASS_NAME}" -D "NODE_NAME=${NODE_NAME}" -D "OUTPUT_FILE=${OUTPUT_FILE}" + -D "LIFECYCLE=OFF" -P "${CMAKE_SOURCE_DIR}/cmake/GenerateFilterChainNode.cmake" DEPENDS "${CMAKE_CURRENT_SOURCE_DIR}/cmake/FilterChainNode.cpp.in" @@ -91,10 +95,42 @@ function(generate_filter_chain_source NODE_NAME) if (SOURCES) target_sources(${NODE_NAME}_component PRIVATE ${SOURCES}) endif () + + if (NOT NO_LIFECYCLE) + set(LIFECYCLE_NODE_NAME "${NODE_NAME}_lifecycle") + + set(LIFECYCLE_CLASS_NAME "Lifecycle${CLASS_NAME}") + set(LIFECYCLE_FILE_NAME "Lifecycle${FILE_NAME}") + + set(LIFECYCLE_OUTPUT_FILE "${PROJECT_BINARY_DIR}/${LIFECYCLE_FILE_NAME}") + + add_custom_command( + OUTPUT "${LIFECYCLE_OUTPUT_FILE}" + COMMAND ${CMAKE_COMMAND} + -D "PROJECT_SOURCE_DIR=${PROJECT_SOURCE_DIR}" + -D "MESSAGE_TYPE=${MESSAGE_TYPE}" + -D "HEADER_NAME=${HEADER_NAME}" + -D "BASE_FILTER=${BASE_FILTER}" + -D "CLASS_NAME=${LIFECYCLE_CLASS_NAME}" + -D "NODE_NAME=${LIFECYCLE_NODE_NAME}" + -D "OUTPUT_FILE=${LIFECYCLE_OUTPUT_FILE}" + -D "LIFECYCLE=ON" + -P "${CMAKE_SOURCE_DIR}/cmake/GenerateFilterChainNode.cmake" + DEPENDS + "${CMAKE_CURRENT_SOURCE_DIR}/cmake/LifecycleFilterChainNode.cpp.in" + "${CMAKE_SOURCE_DIR}/cmake/GenerateFilterChainNode.cmake" + VERBATIM + ) + + add_filter_chain_node(${LIFECYCLE_NODE_NAME} "${LIFECYCLE_CLASS_NAME}" "${LIFECYCLE_OUTPUT_FILE}") + + if (SOURCES) + target_sources(${LIFECYCLE_NODE_NAME}_component PRIVATE ${SOURCES}) + endif () + endif () endfunction() generate_filter_chain_source("compressed_image" HEADER_NAME "compressed_image" MESSAGE_TYPE "CompressedImage") -generate_filter_chain_source("image" HEADER_NAME "image" MESSAGE_TYPE "Image" BASE_FILTER "ImageFilterChainBase" SOURCES src/ImageFilterChainBase.cpp) generate_filter_chain_source("imu" HEADER_NAME "imu" MESSAGE_TYPE "Imu") generate_filter_chain_source("joy" HEADER_NAME "joy" MESSAGE_TYPE "Joy") generate_filter_chain_source("scan" HEADER_NAME "laser_scan" MESSAGE_TYPE "LaserScan") @@ -102,10 +138,11 @@ generate_filter_chain_source("magnetic_field" HEADER_NAME "magnetic_field" MESSA generate_filter_chain_source("multi_echo_scan" HEADER_NAME "multi_echo_laser_scan" MESSAGE_TYPE "MultiEchoLaserScan") generate_filter_chain_source("navsat_fix" HEADER_NAME "nav_sat_fix" MESSAGE_TYPE "NavSatFix") generate_filter_chain_source("pointcloud" HEADER_NAME "point_cloud" MESSAGE_TYPE "PointCloud") -generate_filter_chain_source("pointcloud2" HEADER_NAME "point_cloud2" MESSAGE_TYPE "PointCloud2" BASE_FILTER "PointCloud2FilterChainBase" SOURCES src/PointCloud2FilterChainBase.cpp) generate_filter_chain_source("range" HEADER_NAME "range" MESSAGE_TYPE "Range") generate_filter_chain_source("relative_humidity" HEADER_NAME "relative_humidity" MESSAGE_TYPE "RelativeHumidity") generate_filter_chain_source("temperature" HEADER_NAME "temperature" MESSAGE_TYPE "Temperature") +add_filter_chain_node("image" "ImageFilterChainNode" src/ImageFilterChainNode.cpp) +add_filter_chain_node("pointcloud2" "PointCloud2FilterChainNode" src/PointCloud2FilterChainNode.cpp) set(filters ChangeHeaderFilter diff --git a/cmake/GenerateFilterChainNode.cmake b/cmake/GenerateFilterChainNode.cmake index 18e97b5..0b3e611 100644 --- a/cmake/GenerateFilterChainNode.cmake +++ b/cmake/GenerateFilterChainNode.cmake @@ -9,4 +9,8 @@ else () set(BASE_INCLUDE "") endif () -configure_file(${PROJECT_SOURCE_DIR}/cmake/FilterChainNode.cpp.in ${OUTPUT_FILE} @ONLY) +if (LIFECYCLE) + configure_file(${PROJECT_SOURCE_DIR}/cmake/LifecycleFilterChainNode.cpp.in ${OUTPUT_FILE} @ONLY) +else () + configure_file(${PROJECT_SOURCE_DIR}/cmake/FilterChainNode.cpp.in ${OUTPUT_FILE} @ONLY) +endif () diff --git a/cmake/LifecycleFilterChainNode.cpp.in b/cmake/LifecycleFilterChainNode.cpp.in new file mode 100644 index 0000000..2b9d295 --- /dev/null +++ b/cmake/LifecycleFilterChainNode.cpp.in @@ -0,0 +1,18 @@ +// SPDX-License-Identifier: BSD-3-Clause +// SPDX-FileCopyrightText: Czech Technical University in Prague + +#include +@BASE_INCLUDE@ +#include <@MESSAGE_HEADER@> + +namespace sensor_filters { + class @CLASS_NAME@ : public LifecycleFilterChainNode<@TEMPLATE_ARGS@> { + public: + @CLASS_NAME@(const rclcpp::NodeOptions& options) : LifecycleFilterChainNode("@NODE_NAME@", options) {} + + explicit @CLASS_NAME@(): LifecycleFilterChainNode("@NODE_NAME@") {} + }; +} + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(sensor_filters::@CLASS_NAME@) diff --git a/include/sensor_filters/FilterChainBase.hpp b/include/sensor_filters/FilterChainBase.hpp index e699efa..1271aff 100644 --- a/include/sensor_filters/FilterChainBase.hpp +++ b/include/sensor_filters/FilterChainBase.hpp @@ -10,115 +10,97 @@ #include #include -#include +#include namespace sensor_filters { template class FilterChainBase { protected: - std::shared_ptr> inputSubscriber; - std::shared_ptr> outputPublisher; - rclcpp::Node::SharedPtr node; + std::string filterChainNamespace; size_t inputQueueSize = 10u; size_t outputQueueSize = 10u; bool usePtrMessages = true; + rclcpp::node_interfaces::NodeBaseInterface::SharedPtr baseInterface; + rclcpp::node_interfaces::NodeClockInterface::SharedPtr clockInterface; + rclcpp::node_interfaces::NodeParametersInterface::SharedPtr paramsInterface; + rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr loggingInterface; + filters::FilterChain filterChain; T msg; public: - FilterChainBase() : - filterChain(std::string(typeid(T).name())) {} + FilterChainBase( + std::string filterChainNamespace, + const long inputQueueSize, + const long outputQueueSize, + const bool usePtrMessages, + rclcpp::node_interfaces::NodeBaseInterface::SharedPtr baseInterface, + rclcpp::node_interfaces::NodeClockInterface::SharedPtr clockInterface, + rclcpp::node_interfaces::NodeParametersInterface::SharedPtr paramsInterface, + rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr loggingInterface + ) : filterChainNamespace(std::move(filterChainNamespace)), inputQueueSize(inputQueueSize), outputQueueSize(outputQueueSize), + usePtrMessages(usePtrMessages), baseInterface(std::move(baseInterface)), clockInterface(std::move(clockInterface)), + paramsInterface(std::move(paramsInterface)), loggingInterface(std::move(loggingInterface)), filterChain(std::string(typeid(T).name())) {} virtual ~FilterChainBase() = default; - virtual void initFilters( - const std::string& filterChainNamespace, - rclcpp::Node::SharedPtr node, - const bool usePtrMessages, - long inputQueueSize, - long outputQueueSize - ) { - if (!this->filterChain.configure(filterChainNamespace, node->get_node_logging_interface(), node->get_node_parameters_interface())) { - RCLCPP_ERROR_STREAM(node->get_logger(), "Configuration of filter chain for " + virtual void configure() { + if (!this->filterChain.configure(filterChainNamespace, loggingInterface, paramsInterface)) { + RCLCPP_ERROR_STREAM(loggingInterface->get_logger(), "Configuration of filter chain for " << typeid(T).name() << " is invalid, the chain will not be run."); throw std::runtime_error("Filter configuration error"); } - - RCLCPP_INFO_STREAM(node->get_logger(), "Configured filter chain of type " << typeid(T).name() << " from namespace " - << node->get_namespace() << "/" - << filterChainNamespace); - - this->node = node; - this->outputQueueSize = outputQueueSize; - this->inputQueueSize = inputQueueSize; - this->usePtrMessages = usePtrMessages; - - this->advertise(); - this->subscribe(); } protected: - virtual void advertise() { - this->outputPublisher = this->node->create_publisher("output", this->outputQueueSize); - } + virtual void advertise(); - virtual void subscribe() { - if (this->usePtrMessages) { - this->inputSubscriber = this->node->template create_subscription( - "input", this->inputQueueSize, - [this](const typename T::UniquePtr& msg) { - FilterChainBase::callbackUnique(msg); - } - ); - } else { - this->inputSubscriber = this->node->template create_subscription( - "input", this->inputQueueSize, - [this](const T& msg) { - FilterChainBase::callbackReference(msg); - } - ); - } - } + virtual void subscribe(); - virtual void publishUnique(typename T::UniquePtr& msg) { - this->outputPublisher->publish(std::move(msg)); - } + virtual bool isActive(); - virtual void publishShared(const typename T::ConstSharedPtr& msg) { - RCLCPP_ERROR_THROTTLE(node->get_logger(), *node->get_clock(), 1000, "must be overriden by child class"); - } + virtual void publishUnique(typename T::UniquePtr& msg); - virtual void publishReference(const T& msg) { - this->outputPublisher->publish(msg); - } + virtual void publishShared(const typename T::ConstSharedPtr& msg); + + virtual void publishReference(const T& msg); virtual void callbackUnique(const typename T::UniquePtr& msgIn) { + if (!isActive()) + return; + typename T::UniquePtr msgOut = std::make_unique(); if (this->filter(*msgIn, *msgOut)) this->publishUnique(msgOut); } virtual void callbackShared(const typename T::ConstSharedPtr& msgIn) { + if (!isActive()) + return; + typename T::SharedPtr msgOut = std::make_shared(); if (this->filter(*msgIn, *msgOut)) this->publishShared(msgOut); } virtual void callbackReference(const T& msgIn) { + if (!isActive()) + return; + if (this->filter(msgIn, this->msg)) this->publishReference(this->msg); } virtual bool filter(const T& msgIn, T& msgOut) { - const auto clock = node->get_clock(); + const auto clock = clockInterface->get_clock(); const auto start = clock->now(); if (!this->filterChain.update(msgIn, msgOut)) { - RCLCPP_ERROR_THROTTLE(node->get_logger(), *clock, 1000, "Filtering data from time %i.%i failed.", + RCLCPP_ERROR_THROTTLE(loggingInterface->get_logger(), *clock, 1000, "Filtering data from time %i.%i failed.", msgIn.header.stamp.sec, msgIn.header.stamp.nanosec); return false; } - RCLCPP_DEBUG_STREAM(node->get_logger(), "Filtering took " << (clock->now() - start).seconds() << " s."); + RCLCPP_DEBUG_STREAM(loggingInterface->get_logger(), "Filtering took " << (clock->now() - start).seconds() << " s."); return true; } }; diff --git a/include/sensor_filters/FilterChainNode.hpp b/include/sensor_filters/FilterChainNode.hpp index b3a139d..71effe6 100644 --- a/include/sensor_filters/FilterChainNode.hpp +++ b/include/sensor_filters/FilterChainNode.hpp @@ -9,28 +9,222 @@ */ #include +#include #include namespace sensor_filters { + // TODO 2026-03-17 (solonovamax): maybe create a FilterChainNodeGeneric template that can be used for both normal & lifecycle nodes? + template > class FilterChainNode : public rclcpp::Node, public Base { public: - explicit FilterChainNode(const std::string& name, const rclcpp::NodeOptions& options) : Node(name, options), Base() { - this->initFilters( - name, this->node, false, + // TODO 2026-03-16 (solonovamax): support parameter callback + explicit FilterChainNode(const std::string& name, const rclcpp::NodeOptions& options) : + Node(name, options), + Base( + name, + this->declare_parameter("input_queue_size", 10), + this->declare_parameter("output_queue_size", 10), + false, + this->get_node_base_interface(), + this->get_node_clock_interface(), + this->get_node_parameters_interface(), + this->get_node_logging_interface() + ) {} + + //! use a composable node instead + [[deprecated]] explicit FilterChainNode(const std::string& name) : + Node(name), + Base( + name, this->declare_parameter("input_queue_size", 10), - this->declare_parameter("output_queue_size", 10) - ); + this->declare_parameter("output_queue_size", 10), + false, + this->get_node_base_interface(), + this->get_node_clock_interface(), + this->get_node_parameters_interface(), + this->get_node_logging_interface() + ) {} + + void configure() override { + Base::configure(); + + publish(); + subscribe(); + } + + virtual void publish() { + this->outputPublisher = create_publisher("output", this->outputQueueSize); + } + + virtual void subscribe() { + if (this->usePtrMessages) { + this->inputSubscriber = create_subscription( + "input", this->inputQueueSize, + [this](const typename T::UniquePtr& msg) { + FilterChainBase::callbackUnique(msg); + } + ); + } else { + this->inputSubscriber = create_subscription( + "input", this->inputQueueSize, + [this](const T& msg) { + FilterChainBase::callbackReference(msg); + } + ); + } + } + + bool isActive() override { + return true; + } + + void publishUnique(typename T::UniquePtr& msg) override { + this->outputPublisher->publish(std::move(msg)); + } + + void publishShared(const typename T::ConstSharedPtr&) override { + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 1000, "must be overridden by child class"); } + void publishReference(const T& msg) override { + this->outputPublisher->publish(msg); + } + + private: + std::shared_ptr> inputSubscriber; + std::shared_ptr> outputPublisher; + }; + + template > + class LifecycleFilterChainNode : public rclcpp_lifecycle::LifecycleNode, public Base { + public: + // TODO 2026-03-16 (solonovamax): support parameter callback + explicit LifecycleFilterChainNode(const std::string& name, const rclcpp::NodeOptions& options) : + LifecycleNode(name, options), + Base( + name, + this->declare_parameter("input_queue_size", 10), + this->declare_parameter("output_queue_size", 10), + false, + this->get_node_base_interface(), + this->get_node_clock_interface(), + this->get_node_parameters_interface(), + this->get_node_logging_interface() + ) {} + //! use a composable node instead - [[deprecated]] explicit FilterChainNode(const std::string& name) : Node(name), Base() { - this->initFilters( - name, this->node, false, + [[deprecated]] explicit LifecycleFilterChainNode(const std::string& name) : + LifecycleNode(name), + Base( + name, this->declare_parameter("input_queue_size", 10), - this->declare_parameter("output_queue_size", 10) - ); + this->declare_parameter("output_queue_size", 10), + false, + this->get_node_base_interface(), + this->get_node_clock_interface(), + this->get_node_parameters_interface(), + this->get_node_logging_interface() + ) {} + + CallbackReturn on_configure(const rclcpp_lifecycle::State&) override { + advertise(); + subscribe(); + + try { + Base::configure(); + } catch (const std::runtime_error&) { + return CallbackReturn::ERROR; + } + + return CallbackReturn::SUCCESS; + } + + CallbackReturn on_cleanup(const rclcpp_lifecycle::State&) override { + // reset state to before on_configure() + this->filterChain.clear(); + outputPublisher.reset(); + inputSubscriber.reset(); + + return CallbackReturn::SUCCESS; + } + + CallbackReturn on_shutdown(const rclcpp_lifecycle::State&) override { + this->filterChain.clear(); + + return CallbackReturn::SUCCESS; + } + + CallbackReturn on_error(const rclcpp_lifecycle::State&) override { + // currently an error can only occur in on_configure, so we don't need to check the previous state + // if other transitions are ever changed so that they can error, then this needs to be updated. + + this->filterChain.clear(); + + return CallbackReturn::SUCCESS; + } + + CallbackReturn on_activate(const rclcpp_lifecycle::State& state) override { + const auto result = LifecycleNode::on_activate(state); + + return result; + } + + CallbackReturn on_deactivate(const rclcpp_lifecycle::State& state) override { + if (const auto result = LifecycleNode::on_deactivate(state); result != CallbackReturn::SUCCESS) + return result; + + return CallbackReturn::SUCCESS; + } + + protected: + void advertise() override { + this->outputPublisher = create_publisher("output", this->outputQueueSize); + } + + void subscribe() override { + if (this->usePtrMessages) { + this->inputSubscriber = create_subscription( + "input", this->inputQueueSize, + [this](const typename T::UniquePtr& msg) { + FilterChainBase::callbackUnique(msg); + } + ); + } else { + this->inputSubscriber = create_subscription( + "input", this->inputQueueSize, + [this](const T& msg) { + FilterChainBase::callbackReference(msg); + } + ); + } + } + + bool isActive() override { + return this->outputPublisher->is_activated(); + } + + void publishUnique(typename T::UniquePtr& msg) override { + if (!this->outputPublisher->is_activated()) + return; + + this->outputPublisher->publish(std::move(msg)); + } + + void publishShared(const typename T::ConstSharedPtr&) override { + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 1000, "must be overridden by child class"); + } + + void publishReference(const T& msg) override { + if (!this->outputPublisher->is_activated()) + return; + + this->outputPublisher->publish(msg); } + + private: + std::shared_ptr> inputSubscriber; + std::shared_ptr> outputPublisher; }; //! this method is deprecated, and instead a composable node should be used @@ -38,6 +232,15 @@ namespace sensor_filters { [[deprecated]] void spinFilterChain(const std::string& name, const int argc, char** argv) { rclcpp::init(argc, argv); const auto node = std::make_shared>(name); + node->configure(); + rclcpp::spin(node); + } + + //! this method is deprecated, and instead a composable node should be used + template > + [[deprecated]] void spinLifecycleFilterChain(const std::string& name, const int argc, char** argv) { + rclcpp::init(argc, argv); + const auto node = std::make_shared>(name); rclcpp::spin(node); } } diff --git a/include/sensor_filters/ImageFilterChainBase.hpp b/include/sensor_filters/ImageFilterChainBase.hpp deleted file mode 100644 index 9826384..0000000 --- a/include/sensor_filters/ImageFilterChainBase.hpp +++ /dev/null @@ -1,43 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#pragma once - -/** - * \file - * \brief Specialized base for Image filter chains that uses image_transport. - */ - -#include -#include -#include -#include -#include -#include -#include - -namespace sensor_filters { - class ImageFilterChainBase : public FilterChainBase { - public: - ImageFilterChainBase() {} - - void initFilters( - const std::string& filterChainNamespace, - rclcpp::Node::SharedPtr node, - bool useSharedPtrMessages, - long inputQueueSize, - long outputQueueSize - ) override; - - protected: - std::unique_ptr it; - image_transport::Publisher itPublisher; - image_transport::Subscriber itSubscriber; - - void advertise() override; - - void subscribe() override; - - void publishShared(const sensor_msgs::msg::Image::ConstSharedPtr& msg) override; - }; -} diff --git a/include/sensor_filters/PointCloud2FilterChainBase.hpp b/include/sensor_filters/PointCloud2FilterChainBase.hpp deleted file mode 100644 index 0b8929e..0000000 --- a/include/sensor_filters/PointCloud2FilterChainBase.hpp +++ /dev/null @@ -1,43 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#pragma once - -/** - * \file - * \brief Specialized base for PointCloud2 filter chains that uses point_cloud_transport. - */ - -#include -#include -#include -#include -#include -#include -#include - -namespace sensor_filters { - class PointCloud2FilterChainBase : public FilterChainBase { - public: - PointCloud2FilterChainBase() {} - - void initFilters( - const std::string& filterChainNamespace, - rclcpp::Node::SharedPtr node, - bool useSharedPtrMessages, - long inputQueueSize, - long outputQueueSize - ) override; - - protected: - std::unique_ptr pct; - point_cloud_transport::Publisher pctPublisher; - point_cloud_transport::Subscriber pctSubscriber; - - void advertise() override; - - void subscribe() override; - - void publishShared(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) override; - }; -} diff --git a/package.xml b/package.xml index 7099c53..fdc2fb4 100644 --- a/package.xml +++ b/package.xml @@ -20,6 +20,8 @@ SPDX-FileCopyrightText: Czech Technical University in Prague filters rclcpp rclcpp_components + rclcpp_lifecycle + lifecycle_msgs sensor_msgs backward_ros diff --git a/src/ImageFilterChainBase.cpp b/src/ImageFilterChainBase.cpp deleted file mode 100644 index 6967eb3..0000000 --- a/src/ImageFilterChainBase.cpp +++ /dev/null @@ -1,40 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include -#include -#include -#include -#include - -namespace sensor_filters { - void ImageFilterChainBase::initFilters( - const std::string& filterChainNamespace, - rclcpp::Node::SharedPtr node, - const bool useSharedPtrMessages, - const long inputQueueSize, - const long outputQueueSize - ) { - // TODO 2026-02-23 (solonovamax): offer parameter to advertise camera topic? - this->it = std::make_unique(node); - FilterChainBase::initFilters(filterChainNamespace, node, useSharedPtrMessages, inputQueueSize, outputQueueSize); - } - - void ImageFilterChainBase::advertise() { - this->itPublisher = this->it->advertise("output", this->outputQueueSize); - } - - void ImageFilterChainBase::subscribe() { - this->itSubscriber = this->it->subscribe( - "input", this->inputQueueSize, - [this](const typename sensor_msgs::msg::Image::ConstSharedPtr& msg) { - this->callbackShared(msg); - } - ); - } - - void ImageFilterChainBase::publishShared(const sensor_msgs::msg::Image::ConstSharedPtr& msg) { - this->itPublisher.publish(msg); - } -} diff --git a/src/ImageFilterChainNode.cpp b/src/ImageFilterChainNode.cpp new file mode 100644 index 0000000..7e2aa11 --- /dev/null +++ b/src/ImageFilterChainNode.cpp @@ -0,0 +1,47 @@ +// SPDX-License-Identifier: BSD-3-Clause +// SPDX-FileCopyrightText: Czech Technical University in Prague + +#include +#include +#include +#include +#include + +namespace sensor_filters { + class ImageFilterChainNode : public FilterChainNode { + public: + explicit ImageFilterChainNode(const rclcpp::NodeOptions& options) : FilterChainNode("Image_filter_chain", options) { + this->it = std::make_unique(this->shared_from_this()); + } + + [[deprecated]] explicit ImageFilterChainNode() : FilterChainNode("Image_filter_chain") { + this->it = std::make_unique(this->shared_from_this()); + } + + protected: + void publish() override { + this->itPublisher = this->it->advertise("output", this->outputQueueSize); + } + + void subscribe() override { + this->itSubscriber = this->it->subscribe( + "input", this->inputQueueSize, + [this](const sensor_msgs::msg::Image::ConstSharedPtr& msg) { + this->callbackShared(msg); + } + ); + } + + void publishShared(const sensor_msgs::msg::Image::ConstSharedPtr& msg) override { + this->itPublisher.publish(msg); + } + + private: + std::unique_ptr it; + image_transport::Publisher itPublisher; + image_transport::Subscriber itSubscriber; + }; +} + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(sensor_filters::ImageFilterChainNode) diff --git a/src/PointCloud2FilterChainBase.cpp b/src/PointCloud2FilterChainBase.cpp deleted file mode 100644 index 46422aa..0000000 --- a/src/PointCloud2FilterChainBase.cpp +++ /dev/null @@ -1,38 +0,0 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague - -#include -#include -#include -#include -#include - -namespace sensor_filters { - void PointCloud2FilterChainBase::initFilters( - const std::string& filterChainNamespace, - rclcpp::Node::SharedPtr node, - const bool useSharedPtrMessages, - const long inputQueueSize, - const long outputQueueSize - ) { - this->pct = std::make_unique(node); - FilterChainBase::initFilters(filterChainNamespace, node, useSharedPtrMessages, inputQueueSize, outputQueueSize); - } - - void PointCloud2FilterChainBase::advertise() { - this->pctPublisher = this->pct->advertise("output", this->outputQueueSize); - } - - void PointCloud2FilterChainBase::subscribe() { - this->pctSubscriber = this->pct->subscribe( - "input", this->inputQueueSize, - [this](const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) { - PointCloud2FilterChainBase::callbackShared(msg); - } - ); - } - - void PointCloud2FilterChainBase::publishShared(const typename sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) { - this->pctPublisher.publish(msg); - } -} diff --git a/src/PointCloud2FilterChainNode.cpp b/src/PointCloud2FilterChainNode.cpp new file mode 100644 index 0000000..f9db0b6 --- /dev/null +++ b/src/PointCloud2FilterChainNode.cpp @@ -0,0 +1,47 @@ +// SPDX-License-Identifier: BSD-3-Clause +// SPDX-FileCopyrightText: Czech Technical University in Prague + +#include +#include +#include +#include +#include + +namespace sensor_filters { + class PointCloud2FilterChainNode : public FilterChainNode { + public: + explicit PointCloud2FilterChainNode(const rclcpp::NodeOptions& options) : FilterChainNode("pointcloud2_filter_chain", options) { + this->pct = std::make_unique(this->shared_from_this()); + } + + [[deprecated]] explicit PointCloud2FilterChainNode() : FilterChainNode("pointcloud2_filter_chain") { + this->pct = std::make_unique(this->shared_from_this()); + } + + protected: + void publish() override { + this->pctPublisher = this->pct->advertise("output", this->outputQueueSize); + } + + void subscribe() override { + this->pctSubscriber = this->pct->subscribe( + "input", this->inputQueueSize, + [this](const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) { + PointCloud2FilterChainNode::callbackShared(msg); + } + ); + } + + void publishShared(const typename sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg) override { + this->pctPublisher.publish(msg); + } + + private: + std::unique_ptr pct; + point_cloud_transport::Publisher pctPublisher; + point_cloud_transport::Subscriber pctSubscriber; + }; +} + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(sensor_filters::PointCloud2FilterChainNode) From 10f1aba268ae89277c3a672280ec7b6cd637820f Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 17 Mar 2026 12:57:23 -0400 Subject: [PATCH 14/23] oops, forgot to add this to the CMakeLists.txt Signed-off-by: solonovamax --- CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index b941f94..a855860 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -64,6 +64,7 @@ function(generate_filter_chain_source NODE_NAME) set(HEADER_NAME "${arg_HEADER_NAME}") set(MESSAGE_TYPE "${arg_MESSAGE_TYPE}") set(SOURCES "${arg_SOURCES}") + set(NO_LIFECYCLE "${arg_NO_LIFECYCLE}") set(NODE_NAME "${NODE_NAME}_filter_chain") From 46f2ff04a5d3decd85e76807b695d39e5ac86682 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 17 Mar 2026 13:07:15 -0400 Subject: [PATCH 15/23] Fix some things I forgot to change Signed-off-by: solonovamax --- cmake/FilterChainNode.cpp.in | 8 ++++++-- cmake/LifecycleFilterChainNode.cpp.in | 8 ++++++-- include/sensor_filters/FilterChainNode.hpp | 6 +++--- src/ImageFilterChainNode.cpp | 4 +++- src/PointCloud2FilterChainNode.cpp | 4 +++- 5 files changed, 21 insertions(+), 9 deletions(-) diff --git a/cmake/FilterChainNode.cpp.in b/cmake/FilterChainNode.cpp.in index 37d1f8e..4978ea9 100644 --- a/cmake/FilterChainNode.cpp.in +++ b/cmake/FilterChainNode.cpp.in @@ -8,9 +8,13 @@ namespace sensor_filters { class @CLASS_NAME@ : public FilterChainNode<@TEMPLATE_ARGS@> { public: - @CLASS_NAME@(const rclcpp::NodeOptions& options) : FilterChainNode("@NODE_NAME@", options) {} + @CLASS_NAME@(const rclcpp::NodeOptions& options) : FilterChainNode("@NODE_NAME@", options) { + @CLASS_NAME@::configure(); + } - explicit @CLASS_NAME@(): FilterChainNode("@NODE_NAME@") {} + explicit @CLASS_NAME@(): FilterChainNode("@NODE_NAME@") { + @CLASS_NAME@::configure(); + } }; } diff --git a/cmake/LifecycleFilterChainNode.cpp.in b/cmake/LifecycleFilterChainNode.cpp.in index 2b9d295..59837cd 100644 --- a/cmake/LifecycleFilterChainNode.cpp.in +++ b/cmake/LifecycleFilterChainNode.cpp.in @@ -8,9 +8,13 @@ namespace sensor_filters { class @CLASS_NAME@ : public LifecycleFilterChainNode<@TEMPLATE_ARGS@> { public: - @CLASS_NAME@(const rclcpp::NodeOptions& options) : LifecycleFilterChainNode("@NODE_NAME@", options) {} + @CLASS_NAME@(const rclcpp::NodeOptions& options) : LifecycleFilterChainNode("@NODE_NAME@", options) { + @CLASS_NAME@::configure(); + } - explicit @CLASS_NAME@(): LifecycleFilterChainNode("@NODE_NAME@") {} + explicit @CLASS_NAME@(): LifecycleFilterChainNode("@NODE_NAME@") { + @CLASS_NAME@::configure(); + } }; } diff --git a/include/sensor_filters/FilterChainNode.hpp b/include/sensor_filters/FilterChainNode.hpp index 71effe6..492e7f0 100644 --- a/include/sensor_filters/FilterChainNode.hpp +++ b/include/sensor_filters/FilterChainNode.hpp @@ -49,15 +49,15 @@ namespace sensor_filters { void configure() override { Base::configure(); - publish(); + advertise(); subscribe(); } - virtual void publish() { + void advertise() override { this->outputPublisher = create_publisher("output", this->outputQueueSize); } - virtual void subscribe() { + void subscribe() override { if (this->usePtrMessages) { this->inputSubscriber = create_subscription( "input", this->inputQueueSize, diff --git a/src/ImageFilterChainNode.cpp b/src/ImageFilterChainNode.cpp index 7e2aa11..607ab13 100644 --- a/src/ImageFilterChainNode.cpp +++ b/src/ImageFilterChainNode.cpp @@ -12,14 +12,16 @@ namespace sensor_filters { public: explicit ImageFilterChainNode(const rclcpp::NodeOptions& options) : FilterChainNode("Image_filter_chain", options) { this->it = std::make_unique(this->shared_from_this()); + ImageFilterChainNode::configure(); } [[deprecated]] explicit ImageFilterChainNode() : FilterChainNode("Image_filter_chain") { this->it = std::make_unique(this->shared_from_this()); + ImageFilterChainNode::configure(); } protected: - void publish() override { + void advertise() override { this->itPublisher = this->it->advertise("output", this->outputQueueSize); } diff --git a/src/PointCloud2FilterChainNode.cpp b/src/PointCloud2FilterChainNode.cpp index f9db0b6..8d0a14d 100644 --- a/src/PointCloud2FilterChainNode.cpp +++ b/src/PointCloud2FilterChainNode.cpp @@ -12,14 +12,16 @@ namespace sensor_filters { public: explicit PointCloud2FilterChainNode(const rclcpp::NodeOptions& options) : FilterChainNode("pointcloud2_filter_chain", options) { this->pct = std::make_unique(this->shared_from_this()); + PointCloud2FilterChainNode::configure(); } [[deprecated]] explicit PointCloud2FilterChainNode() : FilterChainNode("pointcloud2_filter_chain") { this->pct = std::make_unique(this->shared_from_this()); + PointCloud2FilterChainNode::configure(); } protected: - void publish() override { + void advertise() override { this->pctPublisher = this->pct->advertise("output", this->outputQueueSize); } From 2a4b06cc4057f0c0188a6a0466191a0fc505b356 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 17 Mar 2026 13:18:46 -0400 Subject: [PATCH 16/23] oops, lifecycle nodes didn't need that Signed-off-by: solonovamax --- cmake/LifecycleFilterChainNode.cpp.in | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/cmake/LifecycleFilterChainNode.cpp.in b/cmake/LifecycleFilterChainNode.cpp.in index 59837cd..2b9d295 100644 --- a/cmake/LifecycleFilterChainNode.cpp.in +++ b/cmake/LifecycleFilterChainNode.cpp.in @@ -8,13 +8,9 @@ namespace sensor_filters { class @CLASS_NAME@ : public LifecycleFilterChainNode<@TEMPLATE_ARGS@> { public: - @CLASS_NAME@(const rclcpp::NodeOptions& options) : LifecycleFilterChainNode("@NODE_NAME@", options) { - @CLASS_NAME@::configure(); - } + @CLASS_NAME@(const rclcpp::NodeOptions& options) : LifecycleFilterChainNode("@NODE_NAME@", options) {} - explicit @CLASS_NAME@(): LifecycleFilterChainNode("@NODE_NAME@") { - @CLASS_NAME@::configure(); - } + explicit @CLASS_NAME@(): LifecycleFilterChainNode("@NODE_NAME@") {} }; } From ebe0dce40f2f27ed67189f308252795429b9df3e Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 17 Mar 2026 13:21:23 -0400 Subject: [PATCH 17/23] Clean up template sources Signed-off-by: solonovamax --- cmake/FilterChainNode.cpp.in | 4 ++-- cmake/LifecycleFilterChainNode.cpp.in | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/cmake/FilterChainNode.cpp.in b/cmake/FilterChainNode.cpp.in index 4978ea9..e7456fd 100644 --- a/cmake/FilterChainNode.cpp.in +++ b/cmake/FilterChainNode.cpp.in @@ -8,11 +8,11 @@ namespace sensor_filters { class @CLASS_NAME@ : public FilterChainNode<@TEMPLATE_ARGS@> { public: - @CLASS_NAME@(const rclcpp::NodeOptions& options) : FilterChainNode("@NODE_NAME@", options) { + explicit @CLASS_NAME@(const rclcpp::NodeOptions& options) : FilterChainNode("@NODE_NAME@", options) { @CLASS_NAME@::configure(); } - explicit @CLASS_NAME@(): FilterChainNode("@NODE_NAME@") { + [[deprecated]] explicit @CLASS_NAME@(): FilterChainNode("@NODE_NAME@") { @CLASS_NAME@::configure(); } }; diff --git a/cmake/LifecycleFilterChainNode.cpp.in b/cmake/LifecycleFilterChainNode.cpp.in index 2b9d295..0c25e24 100644 --- a/cmake/LifecycleFilterChainNode.cpp.in +++ b/cmake/LifecycleFilterChainNode.cpp.in @@ -8,9 +8,9 @@ namespace sensor_filters { class @CLASS_NAME@ : public LifecycleFilterChainNode<@TEMPLATE_ARGS@> { public: - @CLASS_NAME@(const rclcpp::NodeOptions& options) : LifecycleFilterChainNode("@NODE_NAME@", options) {} + explicit @CLASS_NAME@(const rclcpp::NodeOptions& options) : LifecycleFilterChainNode("@NODE_NAME@", options) {} - explicit @CLASS_NAME@(): LifecycleFilterChainNode("@NODE_NAME@") {} + [[deprecated]] explicit @CLASS_NAME@(): LifecycleFilterChainNode("@NODE_NAME@") {} }; } From a55f227549cec96afe3125f1fb3d4f59dd1634a1 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 17 Mar 2026 13:40:05 -0400 Subject: [PATCH 18/23] Fix compilation on rolling Signed-off-by: solonovamax --- CMakeLists.txt | 22 +++++++++++++++++----- 1 file changed, 17 insertions(+), 5 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a855860..43a02d5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -30,16 +30,29 @@ foreach (dependency IN ITEMS ${DEPENDENCIES}) find_package(${dependency} REQUIRED) endforeach () +set(LIBRARY_TARGETS + ${rclcpp_TARGETS} + ${rclcpp_components_TARGETS} + ${rclcpp_lifecycle_TARGETS} + ${lifecycle_msgs_TARGETS} + ${filters_TARGETS} + ${sensor_msgs_TARGETS} + ${image_transport_TARGETS} + ${point_cloud_transport_TARGETS} + ${backward_ros_TARGETS} +) + +message("LIBRARY_TARGETS=${LIBRARY_TARGETS}") + include_directories(include include/${PROJECT_NAME}) function(add_filter_chain_node TARGET_NAME CLASS_NAME FILENAME) list(APPEND NODE_TARGETS ${TARGET_NAME}) add_library("${TARGET_NAME}_component" SHARED "${FILENAME}") - rclcpp_components_register_node(${TARGET_NAME}_component PLUGIN "sensor_filters::${CLASS_NAME}" EXECUTABLE ${TARGET_NAME}) + rclcpp_components_register_node("${TARGET_NAME}_component" PLUGIN "sensor_filters::${CLASS_NAME}" EXECUTABLE ${TARGET_NAME}) #add_executable(${TARGET_NAME} "${FILENAME}") - #target_link_libraries(${TARGET_NAME} ${DEPENDENCIES}) - ament_target_dependencies("${TARGET_NAME}_component" ${DEPENDENCIES}) + target_link_libraries("${TARGET_NAME}_component" PUBLIC ${LIBRARY_TARGETS}) #install(TARGETS ${TARGET_NAME} # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} @@ -153,8 +166,7 @@ foreach (filter IN LISTS filters) list(APPEND FILTER_LIBRARIES ${filter}) add_library(${filter} src/filters/${filter}.cpp) - ament_target_dependencies(${filter} ${DEPENDENCIES}) - # target_link_libraries(${filter} ${catkin_LIBRARIES}) + target_link_libraries(${filter} PUBLIC ${LIBRARY_TARGETS}) pluginlib_export_plugin_description_file(filters ${filter}.xml) endforeach () From e53d9a078a84d14e3dcb2abf1c5a05df729a1ac4 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 17 Mar 2026 14:03:16 -0400 Subject: [PATCH 19/23] Fix names of image & pointcloud2 filter chain nodes Signed-off-by: solonovamax --- CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 43a02d5..5a588e7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -155,8 +155,8 @@ generate_filter_chain_source("pointcloud" HEADER_NAME "point_cloud" MESSAGE_TYPE generate_filter_chain_source("range" HEADER_NAME "range" MESSAGE_TYPE "Range") generate_filter_chain_source("relative_humidity" HEADER_NAME "relative_humidity" MESSAGE_TYPE "RelativeHumidity") generate_filter_chain_source("temperature" HEADER_NAME "temperature" MESSAGE_TYPE "Temperature") -add_filter_chain_node("image" "ImageFilterChainNode" src/ImageFilterChainNode.cpp) -add_filter_chain_node("pointcloud2" "PointCloud2FilterChainNode" src/PointCloud2FilterChainNode.cpp) +add_filter_chain_node("image_filter_chain" "ImageFilterChainNode" src/ImageFilterChainNode.cpp) +add_filter_chain_node("pointcloud2_filter_chain" "PointCloud2FilterChainNode" src/PointCloud2FilterChainNode.cpp) set(filters ChangeHeaderFilter From 55f913af28104db686694c614f3752d82e81ea7c Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 17 Mar 2026 14:07:17 -0400 Subject: [PATCH 20/23] Remove debug message in CMakeLists.txt I left in accidentally Signed-off-by: solonovamax --- CMakeLists.txt | 2 -- 1 file changed, 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5a588e7..b9e3919 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -42,8 +42,6 @@ set(LIBRARY_TARGETS ${backward_ros_TARGETS} ) -message("LIBRARY_TARGETS=${LIBRARY_TARGETS}") - include_directories(include include/${PROJECT_NAME}) function(add_filter_chain_node TARGET_NAME CLASS_NAME FILENAME) From a68a2e79edbfaf85dac051b95aaf6142da3c7aa9 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 17 Mar 2026 14:26:23 -0400 Subject: [PATCH 21/23] Fix runtime issues with nodes Signed-off-by: solonovamax --- CMakeLists.txt | 2 +- include/sensor_filters/FilterChainBase.hpp | 12 ++++++------ 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b9e3919..704cd34 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -56,7 +56,7 @@ function(add_filter_chain_node TARGET_NAME CLASS_NAME FILENAME) # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} #) - install(TARGETS ${TARGET_NAME} + install(TARGETS "${TARGET_NAME}_component" ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin diff --git a/include/sensor_filters/FilterChainBase.hpp b/include/sensor_filters/FilterChainBase.hpp index 1271aff..a2b701e 100644 --- a/include/sensor_filters/FilterChainBase.hpp +++ b/include/sensor_filters/FilterChainBase.hpp @@ -54,17 +54,17 @@ namespace sensor_filters { } protected: - virtual void advertise(); + virtual void advertise() = 0; - virtual void subscribe(); + virtual void subscribe() = 0; - virtual bool isActive(); + virtual bool isActive() = 0; - virtual void publishUnique(typename T::UniquePtr& msg); + virtual void publishUnique(typename T::UniquePtr& msg) = 0; - virtual void publishShared(const typename T::ConstSharedPtr& msg); + virtual void publishShared(const typename T::ConstSharedPtr& msg) = 0; - virtual void publishReference(const T& msg); + virtual void publishReference(const T& msg) = 0; virtual void callbackUnique(const typename T::UniquePtr& msgIn) { if (!isActive()) From 41252e2b553aa0fa49b03e4f4ec98444b1a43ded Mon Sep 17 00:00:00 2001 From: solonovamax Date: Tue, 17 Mar 2026 14:51:22 -0400 Subject: [PATCH 22/23] Fix bug in change header filter, where absolute timestamps were incorrectly converting time Signed-off-by: solonovamax --- src/filters/ChangeHeaderFilter.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/src/filters/ChangeHeaderFilter.cpp b/src/filters/ChangeHeaderFilter.cpp index 148e596..9cefb3b 100644 --- a/src/filters/ChangeHeaderFilter.cpp +++ b/src/filters/ChangeHeaderFilter.cpp @@ -1,6 +1,7 @@ // SPDX-License-Identifier: BSD-3-Clause // SPDX-FileCopyrightText: Czech Technical University in Prague +#include #include #include #include @@ -29,8 +30,10 @@ namespace sensor_filters { if (this->getParam("stamp_relative", stampParam)) this->newStampRel = rclcpp::Duration::from_seconds(stampParam); - if (this->getParam("stamp", stampParam)) - this->newStampAbs = rclcpp::Time(stampParam); + if (this->getParam("stamp", stampParam)) { + const auto nanos = std::chrono::duration_cast(std::chrono::duration(stampParam)); + this->newStampAbs = rclcpp::Time(nanos.count()); + } } return true; From a01491d62b7b0998e396a304847bdf0ffabe3775 Mon Sep 17 00:00:00 2001 From: solonovamax Date: Thu, 19 Mar 2026 13:25:04 -0400 Subject: [PATCH 23/23] Clean up REGISTER_ALL_MSG_FILTER macro for future use added boost as a build dependency. though it's already a transitive dep. Signed-off-by: solonovamax --- CMakeLists.txt | 3 +++ package.xml | 1 + src/filters/ChangeHeaderFilter.cpp | 2 +- src/filters/include_all_msgs.hpp | 38 +++++++++++++++++++----------- 4 files changed, 29 insertions(+), 15 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 704cd34..c935ad0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -26,11 +26,14 @@ set(DEPENDENCIES find_package(ament_cmake REQUIRED) +find_package(Boost CONFIG) + foreach (dependency IN ITEMS ${DEPENDENCIES}) find_package(${dependency} REQUIRED) endforeach () set(LIBRARY_TARGETS + ${boost_TARGETS} ${rclcpp_TARGETS} ${rclcpp_components_TARGETS} ${rclcpp_lifecycle_TARGETS} diff --git a/package.xml b/package.xml index fdc2fb4..8cee55f 100644 --- a/package.xml +++ b/package.xml @@ -24,6 +24,7 @@ SPDX-FileCopyrightText: Czech Technical University in Prague lifecycle_msgs sensor_msgs + boost backward_ros image_transport point_cloud_transport diff --git a/src/filters/ChangeHeaderFilter.cpp b/src/filters/ChangeHeaderFilter.cpp index 9cefb3b..6f09be9 100644 --- a/src/filters/ChangeHeaderFilter.cpp +++ b/src/filters/ChangeHeaderFilter.cpp @@ -74,4 +74,4 @@ namespace sensor_filters { }; } -REGISTER_ALL_MSG_FILTER(sensor_filters::ChangeHeader) +REGISTER_ALL_MSG_FILTERS(sensor_filters::ChangeHeader) diff --git a/src/filters/include_all_msgs.hpp b/src/filters/include_all_msgs.hpp index e127870..41f632f 100644 --- a/src/filters/include_all_msgs.hpp +++ b/src/filters/include_all_msgs.hpp @@ -8,6 +8,7 @@ #pragma once +#include #include #include #include @@ -24,17 +25,26 @@ #include #include -#define REGISTER_ALL_MSG_FILTER(filter) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) \ -PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) +#define SENSOR_MSGS_SEQ \ + (sensor_msgs::msg::CompressedImage) \ + (sensor_msgs::msg::Image) \ + (sensor_msgs::msg::Imu) \ + (sensor_msgs::msg::Joy) \ + (sensor_msgs::msg::LaserScan) \ + (sensor_msgs::msg::MagneticField) \ + (sensor_msgs::msg::MultiEchoLaserScan) \ + (sensor_msgs::msg::NavSatFix) \ + (sensor_msgs::msg::PointCloud) \ + (sensor_msgs::msg::PointCloud2) \ + (sensor_msgs::msg::Range) \ + (sensor_msgs::msg::RelativeHumidity) \ + (sensor_msgs::msg::Temperature) + +#define REGISTER_MSG_FILTER(r, filter, msg) \ + PLUGINLIB_EXPORT_CLASS(filter, filters::FilterBase) + +#define REGISTER_MSG_FILTERS(filter, msg_seq) \ + BOOST_PP_SEQ_FOR_EACH(REGISTER_MSG_FILTER, filter, msg_seq) + +#define REGISTER_ALL_MSG_FILTERS(filter) \ + REGISTER_MSG_FILTERS(filter, SENSOR_MSGS_SEQ)