Skip to content

Commit

Permalink
Add CostmapFilterInfoServer as a component (#3596)
Browse files Browse the repository at this point in the history
  • Loading branch information
FiIipe committed Jun 5, 2023
1 parent 3a258a6 commit 5eb0a40
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 3 deletions.
1 change: 1 addition & 0 deletions nav2_map_server/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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")

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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)

0 comments on commit 5eb0a40

Please sign in to comment.