diff --git a/nav2_map_server/CMakeLists.txt b/nav2_map_server/CMakeLists.txt index c24e5e5c4d..0a43c13696 100644 --- a/nav2_map_server/CMakeLists.txt +++ b/nav2_map_server/CMakeLists.txt @@ -125,6 +125,7 @@ if(WIN32) YAML_CPP_DLL) endif() +rclcpp_components_register_nodes(${library_name} "nav2_map_server::CostmapFilterInfoServer") rclcpp_components_register_nodes(${library_name} "nav2_map_server::MapSaver") rclcpp_components_register_nodes(${library_name} "nav2_map_server::MapServer") diff --git a/nav2_map_server/include/nav2_map_server/costmap_filter_info_server.hpp b/nav2_map_server/include/nav2_map_server/costmap_filter_info_server.hpp index 14a69ad229..26f1153536 100644 --- a/nav2_map_server/include/nav2_map_server/costmap_filter_info_server.hpp +++ b/nav2_map_server/include/nav2_map_server/costmap_filter_info_server.hpp @@ -29,8 +29,10 @@ class CostmapFilterInfoServer : public nav2_util::LifecycleNode public: /** * @brief Constructor for the nav2_map_server::CostmapFilterInfoServer + * @param options Additional options to control creation of the node. */ - CostmapFilterInfoServer(); + explicit CostmapFilterInfoServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); + /** * @brief Destructor for the nav2_map_server::CostmapFilterInfoServer */ diff --git a/nav2_map_server/src/costmap_filter_info/costmap_filter_info_server.cpp b/nav2_map_server/src/costmap_filter_info/costmap_filter_info_server.cpp index f6671b0291..ae917b211f 100644 --- a/nav2_map_server/src/costmap_filter_info/costmap_filter_info_server.cpp +++ b/nav2_map_server/src/costmap_filter_info/costmap_filter_info_server.cpp @@ -24,8 +24,8 @@ namespace nav2_map_server { -CostmapFilterInfoServer::CostmapFilterInfoServer() -: nav2_util::LifecycleNode("costmap_filter_info_server") +CostmapFilterInfoServer::CostmapFilterInfoServer(const rclcpp::NodeOptions & options) +: nav2_util::LifecycleNode("costmap_filter_info_server", "", options) { declare_parameter("filter_info_topic", "costmap_filter_info"); declare_parameter("type", 0); @@ -106,3 +106,10 @@ CostmapFilterInfoServer::on_shutdown(const rclcpp_lifecycle::State & /*state*/) } } // namespace nav2_map_server + +#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(nav2_map_server::CostmapFilterInfoServer)