Skip to content

Commit

Permalink
chore(ndt_scan_matcher): replace entrypoint with rclcpp components macro
Browse files Browse the repository at this point in the history
Signed-off-by: wep21 <[email protected]>
  • Loading branch information
wep21 committed Nov 9, 2023
1 parent bff877c commit 38dc47d
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 39 deletions.
11 changes: 8 additions & 3 deletions localization/ndt_scan_matcher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,16 +26,21 @@ find_package(glog REQUIRED)
find_package(PCL REQUIRED COMPONENTS common io registration)
include_directories(${PCL_INCLUDE_DIRS})

ament_auto_add_executable(ndt_scan_matcher
ament_auto_add_library(ndt_scan_matcher_node SHARED
src/debug.cpp
src/ndt_scan_matcher_node.cpp
src/ndt_scan_matcher_core.cpp
src/map_module.cpp
src/map_update_module.cpp
)

link_directories(${PCL_LIBRARY_DIRS})
target_link_libraries(ndt_scan_matcher ${PCL_LIBRARIES} glog::glog)
target_link_libraries(ndt_scan_matcher_node ${PCL_LIBRARIES} glog::glog)

rclcpp_components_register_node(ndt_scan_matcher_node
PLUGIN "NDTScanMatcher"
EXECUTABLE ndt_scan_matcher
EXECUTOR MultiThreadedExecutor
)

if(BUILD_TESTING)
add_launch_test(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class NDTScanMatcher : public rclcpp::Node
pclomp::MultiGridNormalDistributionsTransform<PointSource, PointTarget>;

public:
NDTScanMatcher();
explicit NDTScanMatcher(const rclcpp::NodeOptions & node_options);

private:
void service_ndt_align(
Expand Down
1 change: 1 addition & 0 deletions localization/ndt_scan_matcher/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<depend>ndt_omp</depend>
<depend>pcl_conversions</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>std_srvs</depend>
Expand Down
7 changes: 5 additions & 2 deletions localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,8 +108,8 @@ bool validate_local_optimal_solution_oscillation(
}

// cspell: ignore degrounded
NDTScanMatcher::NDTScanMatcher()
: Node("ndt_scan_matcher"),
NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & node_options)
: Node("ndt_scan_matcher", node_options),
tf2_broadcaster_(*this),
ndt_ptr_(new NormalDistributionsTransform),
state_ptr_(new std::map<std::string, std::string>),
Expand Down Expand Up @@ -1009,3 +1009,6 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose(

return result_pose_with_cov_msg;
}

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(NDTScanMatcher)
33 changes: 0 additions & 33 deletions localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp

This file was deleted.

0 comments on commit 38dc47d

Please sign in to comment.