Skip to content

Commit

Permalink
feat: components support
Browse files Browse the repository at this point in the history
  • Loading branch information
josegarcia committed May 13, 2024
1 parent 6025d92 commit 2be7a97
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 0 deletions.
3 changes: 3 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@ ament_auto_add_library(laser_scan_filters SHARED src/laser_scan_filters.cpp)
ament_auto_add_library(laser_filter_chains SHARED
src/scan_to_cloud_filter_chain.cpp
src/scan_to_scan_filter_chain.cpp)
rclcpp_components_register_nodes(laser_filter_chains
"ScanToCloudFilterChain"
"ScanToScanFilterChain")

set(FILTER_CHAINS
scan_to_cloud_filter_chain
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
Expand Down
8 changes: 8 additions & 0 deletions src/scan_to_cloud_filter_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,3 +143,11 @@ ScanToCloudFilterChain::scanCallback(

cloud_pub_->publish(filtered_cloud);
}


#include "rclcpp_components/register_node_macro.hpp"

// Register the component with class_loader.
// This acts as a sort of entry point, allowing the component to be discoverable when its library
// is being loaded into a running process.
RCLCPP_COMPONENTS_REGISTER_NODE(ScanToCloudFilterChain)
7 changes: 7 additions & 0 deletions src/scan_to_scan_filter_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,3 +98,10 @@ void ScanToScanFilterChain::callback(
output_pub_->publish(msg_);
}
}

#include "rclcpp_components/register_node_macro.hpp"

// Register the component with class_loader.
// This acts as a sort of entry point, allowing the component to be discoverable when its library
// is being loaded into a running process.
RCLCPP_COMPONENTS_REGISTER_NODE(ScanToScanFilterChain)

0 comments on commit 2be7a97

Please sign in to comment.