Skip to content
Open
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
30 changes: 23 additions & 7 deletions cloudini_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ find_package(point_cloud_transport REQUIRED)
find_package(Draco QUIET)
find_package(pcl_conversions REQUIRED)
find_package(pcl_ros REQUIRED)
find_package(rclcpp_components REQUIRED)

set(PLUGIN_DEPS
pluginlib::pluginlib
Expand Down Expand Up @@ -58,23 +59,38 @@ install(

######### topic converter #########

add_executable(cloudini_topic_converter
add_library(cloudini_topic_converter_component SHARED
src/topic_converter.cpp
)
ament_target_dependencies(cloudini_topic_converter_component
SYSTEM
cloudini_lib
rclcpp_components
)

rclcpp_components_register_node(
cloudini_topic_converter_component
PLUGIN "CloudiniPointcloudConverter"
EXECUTABLE cloudini_topic_converter
)

target_include_directories(cloudini_topic_converter
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
)

target_link_libraries(cloudini_topic_converter
cloudini_ros
cloudini_lib::cloudini_lib
)

install(TARGETS cloudini_topic_converter
install(
TARGETS
cloudini_topic_converter_component
EXPORT export_cloudini_ros
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(
TARGETS
cloudini_topic_converter
RUNTIME DESTINATION lib/cloudini_ros
)

Expand Down
1 change: 1 addition & 0 deletions cloudini_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<depend>mcap_vendor</depend>
<depend>sensor_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>rosbag2_cpp</depend>
<depend>pcl_conversions</depend>
<depend>pcl_ros</depend>
Expand Down
3 changes: 3 additions & 0 deletions cloudini_ros/src/topic_converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <rclcpp/generic_publisher.hpp>
#include <rclcpp/generic_subscription.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>
#include <rosidl_typesupport_cpp/message_type_support.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

Expand Down Expand Up @@ -190,6 +191,8 @@ void CloudiniPointcloudConverter::callback(std::shared_ptr<rclcpp::SerializedMes
count++;
}

RCLCPP_COMPONENTS_REGISTER_NODE(CloudiniPointcloudConverter)

int main(int argc, char** argv) {
// Initialize ROS2 node
rclcpp::init(argc, argv);
Expand Down