Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Stop using ament_target_dependencies. #86

Merged
merged 1 commit into from
May 27, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
60 changes: 19 additions & 41 deletions point_cloud_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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}
Expand All @@ -40,23 +41,24 @@ target_include_directories(${PROJECT_NAME} PUBLIC
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
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
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
Expand Down Expand Up @@ -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)
Expand All @@ -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()

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,18 +32,9 @@
#ifndef POINT_CLOUD_TRANSPORT__LOADER_FWDS_HPP_
#define POINT_CLOUD_TRANSPORT__LOADER_FWDS_HPP_


#include <memory>


// 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 T>
class ClassLoader;
} // namespace pluginlib
#include "pluginlib/class_loader.hpp"

namespace point_cloud_transport
{
Expand All @@ -56,4 +47,5 @@ typedef std::shared_ptr<PubLoader> PubLoaderPtr;
typedef pluginlib::ClassLoader<SubscriberPlugin> SubLoader;
typedef std::shared_ptr<SubLoader> SubLoaderPtr;
} // namespace point_cloud_transport

#endif // POINT_CLOUD_TRANSPORT__LOADER_FWDS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@
#ifndef POINT_CLOUD_TRANSPORT__PUBLISHER_HPP_
#define POINT_CLOUD_TRANSPORT__PUBLISHER_HPP_

#include <string>
#include <memory>
#include <string>

#include "rclcpp/macros.hpp"
#include "rclcpp/node.hpp"
Expand Down
66 changes: 0 additions & 66 deletions point_cloud_transport/include/point_cloud_transport/republish.hpp

This file was deleted.

1 change: 1 addition & 0 deletions point_cloud_transport/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
<depend>rclcpp_components</depend>
<depend>rclcpp</depend>
<depend>rcpputils</depend>
<depend>rmw</depend>
<depend>sensor_msgs</depend>

<test_depend>ament_lint_common</test_depend>
Expand Down
18 changes: 17 additions & 1 deletion point_cloud_transport/src/republish.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<point_cloud_transport::PointCloudTransport> pct;
rclcpp::TimerBase::SharedPtr timer_;
bool initialized_{false};
point_cloud_transport::Subscriber sub;
std::shared_ptr<point_cloud_transport::PublisherPlugin> pub;
std::shared_ptr<point_cloud_transport::Publisher> simple_pub;
};

Republisher::Republisher(const rclcpp::NodeOptions & options)
: Node("point_cloud_republisher", options)
{
Expand Down
2 changes: 2 additions & 0 deletions point_cloud_transport/test/test_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,8 @@

#include <rclcpp/rclcpp.hpp>

#include <sensor_msgs/msg/point_cloud2.hpp>

#include "point_cloud_transport/point_cloud_transport.hpp"

class TestSubscriber : public ::testing::Test
Expand Down