From 980e2e4b544656e7a6495aecb170271a115be6cf Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Fri, 24 May 2024 19:07:10 +0000 Subject: [PATCH] Stop using ament_target_dependencies. We are slowly moving away from its use, so stop using it here. While we are in here, notice some things that makes this easier: 1. pluginlib is absolutely a public dependency of this package. Because of that, we can just rely on the PUBLIC export of it, and we don't need to link it into every test. But that also means we don't need some of the forward-declarations that were in loader_fwds.hpp, as we can just get those through the header file. 2. republish.hpp doesn't really need to exist at all. That's because it is only a header file, but the implementation is in an executable. Thus, no downstream could ever use it. So just remove the file and put the declaration straight into the cpp file. Signed-off-by: Chris Lalancette --- point_cloud_transport/CMakeLists.txt | 60 ++++++----------- .../point_cloud_transport/loader_fwds.hpp | 12 +--- .../point_cloud_transport/publisher.hpp | 2 +- .../point_cloud_transport/republish.hpp | 66 ------------------- point_cloud_transport/package.xml | 1 + point_cloud_transport/src/republish.cpp | 18 ++++- .../test/test_subscriber.cpp | 2 + 7 files changed, 42 insertions(+), 119 deletions(-) delete mode 100644 point_cloud_transport/include/point_cloud_transport/republish.hpp diff --git a/point_cloud_transport/CMakeLists.txt b/point_cloud_transport/CMakeLists.txt index f2444bf..415c236 100644 --- a/point_cloud_transport/CMakeLists.txt +++ b/point_cloud_transport/CMakeLists.txt @@ -18,8 +18,9 @@ find_package(message_filters REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) -find_package(sensor_msgs REQUIRED) find_package(rcpputils REQUIRED) +find_package(rmw REQUIRED) +find_package(sensor_msgs REQUIRED) # Build libpoint_cloud_transport add_library(${PROJECT_NAME} @@ -40,12 +41,12 @@ target_include_directories(${PROJECT_NAME} PUBLIC "$") target_link_libraries(${PROJECT_NAME} PUBLIC message_filters::message_filters + pluginlib::pluginlib rclcpp::rclcpp + rcpputils::rcpputils + rmw::rmw ${sensor_msgs_TARGETS} - rcpputils::rcpputils) -target_link_libraries(${PROJECT_NAME} PRIVATE - pluginlib::pluginlib) - +) target_compile_definitions(${PROJECT_NAME} PRIVATE "POINT_CLOUD_TRANSPORT_BUILDING_DLL") # Build libpoint_cloud_transport_plugins @@ -53,10 +54,11 @@ add_library(${PROJECT_NAME}_plugins src/manifest.cpp ) add_library(${PROJECT_NAME}::${PROJECT_NAME}_plugins ALIAS ${PROJECT_NAME}_plugins) - target_link_libraries(${PROJECT_NAME}_plugins PRIVATE ${PROJECT_NAME} - pluginlib::pluginlib) + pluginlib::pluginlib + ${sensor_msgs_TARGETS} +) add_library(pc_republish_node SHARED src/republish.cpp) target_link_libraries(pc_republish_node PRIVATE @@ -106,7 +108,7 @@ ament_export_include_directories("include/${PROJECT_NAME}") ament_export_targets(export_${PROJECT_NAME}) -ament_export_dependencies(message_filters rclcpp sensor_msgs pluginlib rcpputils) +ament_export_dependencies(message_filters rclcpp sensor_msgs pluginlib rcpputils rmw) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) @@ -121,67 +123,43 @@ if(BUILD_TESTING) ament_add_gtest(${PROJECT_NAME}-publisher test/test_publisher.cpp) if(TARGET ${PROJECT_NAME}-publisher) - target_link_libraries(${PROJECT_NAME}-publisher ${PROJECT_NAME}) - ament_target_dependencies(${PROJECT_NAME}-publisher - pluginlib - ) + target_link_libraries(${PROJECT_NAME}-publisher ${PROJECT_NAME} rclcpp::rclcpp) endif() ament_add_gtest(${PROJECT_NAME}-codec test/test_point_cloud_codec.cpp) if(TARGET ${PROJECT_NAME}-codec) - target_link_libraries(${PROJECT_NAME}-codec ${PROJECT_NAME}) - ament_target_dependencies(${PROJECT_NAME}-codec - pluginlib - ) + target_link_libraries(${PROJECT_NAME}-codec ${PROJECT_NAME} rclcpp::rclcpp ${sensor_msgs_TARGETS}) endif() ament_add_gtest(${PROJECT_NAME}-subscriber test/test_subscriber.cpp) if(TARGET ${PROJECT_NAME}-subscriber) - target_link_libraries(${PROJECT_NAME}-subscriber ${PROJECT_NAME}) - ament_target_dependencies(${PROJECT_NAME}-subscriber - pluginlib - ) + target_link_libraries(${PROJECT_NAME}-subscriber ${PROJECT_NAME} rclcpp::rclcpp ${sensor_msgs_TARGETS}) endif() ament_add_gtest(${PROJECT_NAME}-message_passing test/test_message_passing.cpp) if(TARGET ${PROJECT_NAME}-message_passing) - target_link_libraries(${PROJECT_NAME}-message_passing ${PROJECT_NAME}) - ament_target_dependencies(${PROJECT_NAME}-message_passing - pluginlib - ) + target_link_libraries(${PROJECT_NAME}-message_passing ${PROJECT_NAME} rclcpp::rclcpp ${sensor_msgs_TARGETS}) endif() ament_add_gtest(${PROJECT_NAME}-qos_override test/test_qos_override.cpp) if(TARGET ${PROJECT_NAME}-qos_override) - target_link_libraries(${PROJECT_NAME}-qos_override ${PROJECT_NAME}) - ament_target_dependencies(${PROJECT_NAME}-qos_override - pluginlib - ) + target_link_libraries(${PROJECT_NAME}-qos_override ${PROJECT_NAME} rclcpp::rclcpp ${sensor_msgs_TARGETS}) endif() ament_add_gtest(${PROJECT_NAME}-remapping test/test_remapping.cpp) if(TARGET ${PROJECT_NAME}-remapping) - target_link_libraries(${PROJECT_NAME}-remapping ${PROJECT_NAME}) - ament_target_dependencies(${PROJECT_NAME}-remapping - pluginlib - ) + target_link_libraries(${PROJECT_NAME}-remapping ${PROJECT_NAME} rclcpp::rclcpp ${sensor_msgs_TARGETS}) endif() ament_add_gtest(${PROJECT_NAME}-message-filter test/test_message_filter.cpp) if(TARGET ${PROJECT_NAME}-message-filter) - target_link_libraries(${PROJECT_NAME}-message-filter ${PROJECT_NAME}) - ament_target_dependencies(${PROJECT_NAME}-message-filter - message_filters - pluginlib - ) + target_link_libraries(${PROJECT_NAME}-message-filter + ${PROJECT_NAME} message_filters::message_filters rclcpp::rclcpp ${sensor_msgs_TARGETS}) endif() ament_add_gtest(${PROJECT_NAME}-single_subscriber_publisher test/test_single_subscriber_publisher.cpp) if(TARGET ${PROJECT_NAME}-single_subscriber_publisher) - target_link_libraries(${PROJECT_NAME}-single_subscriber_publisher ${PROJECT_NAME}) - ament_target_dependencies(${PROJECT_NAME}-single_subscriber_publisher - pluginlib - ) + target_link_libraries(${PROJECT_NAME}-single_subscriber_publisher ${PROJECT_NAME} rclcpp::rclcpp ${sensor_msgs_TARGETS}) endif() endif() diff --git a/point_cloud_transport/include/point_cloud_transport/loader_fwds.hpp b/point_cloud_transport/include/point_cloud_transport/loader_fwds.hpp index b84f536..1e33460 100644 --- a/point_cloud_transport/include/point_cloud_transport/loader_fwds.hpp +++ b/point_cloud_transport/include/point_cloud_transport/loader_fwds.hpp @@ -32,18 +32,9 @@ #ifndef POINT_CLOUD_TRANSPORT__LOADER_FWDS_HPP_ #define POINT_CLOUD_TRANSPORT__LOADER_FWDS_HPP_ - #include - -// Forward-declare some classes most users shouldn't care about so that -// point_cloud_transport.hpp doesn't bring them in. - -namespace pluginlib -{ -template -class ClassLoader; -} // namespace pluginlib +#include "pluginlib/class_loader.hpp" namespace point_cloud_transport { @@ -56,4 +47,5 @@ typedef std::shared_ptr PubLoaderPtr; typedef pluginlib::ClassLoader SubLoader; typedef std::shared_ptr SubLoaderPtr; } // namespace point_cloud_transport + #endif // POINT_CLOUD_TRANSPORT__LOADER_FWDS_HPP_ diff --git a/point_cloud_transport/include/point_cloud_transport/publisher.hpp b/point_cloud_transport/include/point_cloud_transport/publisher.hpp index 5eeb2e1..af04d13 100644 --- a/point_cloud_transport/include/point_cloud_transport/publisher.hpp +++ b/point_cloud_transport/include/point_cloud_transport/publisher.hpp @@ -32,8 +32,8 @@ #ifndef POINT_CLOUD_TRANSPORT__PUBLISHER_HPP_ #define POINT_CLOUD_TRANSPORT__PUBLISHER_HPP_ -#include #include +#include #include "rclcpp/macros.hpp" #include "rclcpp/node.hpp" diff --git a/point_cloud_transport/include/point_cloud_transport/republish.hpp b/point_cloud_transport/include/point_cloud_transport/republish.hpp deleted file mode 100644 index 91b6bd6..0000000 --- a/point_cloud_transport/include/point_cloud_transport/republish.hpp +++ /dev/null @@ -1,66 +0,0 @@ -// Copyright (c) 2023, Czech Technical University in Prague -// Copyright (c) 2019, paplhjak -// Copyright (c) 2009, Willow Garage, Inc. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// -// * Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// * Neither the name of the copyright holder nor the names of its -// contributors may be used to endorse or promote products derived from -// this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. -// - -#ifndef POINT_CLOUD_TRANSPORT__REPUBLISH_HPP_ -#define POINT_CLOUD_TRANSPORT__REPUBLISH_HPP_ - -#include - -#include "point_cloud_transport/visibility_control.hpp" - -#include - -#include - -namespace point_cloud_transport -{ - -class Republisher : public rclcpp::Node -{ -public: - //! Constructor - POINT_CLOUD_TRANSPORT_PUBLIC - explicit Republisher(const rclcpp::NodeOptions & options); - -private: - POINT_CLOUD_TRANSPORT_PUBLIC - void initialize(); - - std::shared_ptr pct; - rclcpp::TimerBase::SharedPtr timer_; - bool initialized_{false}; - point_cloud_transport::Subscriber sub; - std::shared_ptr pub; - std::shared_ptr simple_pub; -}; - -} // namespace point_cloud_transport -#endif // POINT_CLOUD_TRANSPORT__REPUBLISH_HPP_ diff --git a/point_cloud_transport/package.xml b/point_cloud_transport/package.xml index 1fdcb37..02bd3d1 100644 --- a/point_cloud_transport/package.xml +++ b/point_cloud_transport/package.xml @@ -24,6 +24,7 @@ rclcpp_components rclcpp rcpputils + rmw sensor_msgs ament_lint_common diff --git a/point_cloud_transport/src/republish.cpp b/point_cloud_transport/src/republish.cpp index a452d04..01f1c88 100644 --- a/point_cloud_transport/src/republish.cpp +++ b/point_cloud_transport/src/republish.cpp @@ -42,13 +42,29 @@ #include "point_cloud_transport/point_cloud_transport.hpp" #include "point_cloud_transport/publisher.hpp" #include "point_cloud_transport/publisher_plugin.hpp" -#include "point_cloud_transport/republish.hpp" #include "point_cloud_transport/subscriber.hpp" using namespace std::chrono_literals; namespace point_cloud_transport { +class Republisher : public rclcpp::Node +{ +public: + //! Constructor + explicit Republisher(const rclcpp::NodeOptions & options); + +private: + void initialize(); + + std::shared_ptr pct; + rclcpp::TimerBase::SharedPtr timer_; + bool initialized_{false}; + point_cloud_transport::Subscriber sub; + std::shared_ptr pub; + std::shared_ptr simple_pub; +}; + Republisher::Republisher(const rclcpp::NodeOptions & options) : Node("point_cloud_republisher", options) { diff --git a/point_cloud_transport/test/test_subscriber.cpp b/point_cloud_transport/test/test_subscriber.cpp index d1bcb1e..429cc3f 100644 --- a/point_cloud_transport/test/test_subscriber.cpp +++ b/point_cloud_transport/test/test_subscriber.cpp @@ -33,6 +33,8 @@ #include +#include + #include "point_cloud_transport/point_cloud_transport.hpp" class TestSubscriber : public ::testing::Test