Skip to content

Commit

Permalink
Register nodes as components (#2562)
Browse files Browse the repository at this point in the history
Signed-off-by: zhenpeng ge <zhenpeng.ge@qq.com>
  • Loading branch information
gezp committed Sep 15, 2021
1 parent 806029d commit 420a6ff
Show file tree
Hide file tree
Showing 17 changed files with 97 additions and 2 deletions.
4 changes: 4 additions & 0 deletions nav2_amcl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ find_package(ament_cmake REQUIRED)
find_package(nav2_common REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(message_filters REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
Expand Down Expand Up @@ -50,6 +51,7 @@ endif()
set(dependencies
rclcpp
rclcpp_lifecycle
rclcpp_components
message_filters
tf2_geometry_msgs
geometry_msgs
Expand Down Expand Up @@ -78,6 +80,8 @@ target_link_libraries(${library_name}
map_lib motions_lib sensors_lib
)

rclcpp_components_register_nodes(${library_name} "nav2_amcl::AmclNode")

install(TARGETS ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand Down
7 changes: 7 additions & 0 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1376,3 +1376,10 @@ AmclNode::initLaserScan()
}

} // namespace nav2_amcl

#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_amcl::AmclNode)
4 changes: 4 additions & 0 deletions nav2_bt_navigator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ find_package(nav2_common REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(nav2_behavior_tree REQUIRED)
Expand Down Expand Up @@ -35,6 +36,7 @@ set(dependencies
rclcpp
rclcpp_action
rclcpp_lifecycle
rclcpp_components
std_msgs
geometry_msgs
nav2_behavior_tree
Expand Down Expand Up @@ -63,6 +65,8 @@ ament_target_dependencies(${library_name}
${dependencies}
)

rclcpp_components_register_nodes(${library_name} "nav2_bt_navigator::BtNavigator")

install(TARGETS ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand Down
7 changes: 7 additions & 0 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,3 +182,10 @@ BtNavigator::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
}

} // namespace nav2_bt_navigator

#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_bt_navigator::BtNavigator)
6 changes: 5 additions & 1 deletion nav2_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ find_package(nav2_common REQUIRED)
find_package(angles REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(std_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav2_msgs REQUIRED)
Expand All @@ -28,14 +29,15 @@ add_executable(${executable_name}

set(library_name ${executable_name}_core)

add_library(${library_name}
add_library(${library_name} SHARED
src/nav2_controller.cpp
)

set(dependencies
angles
rclcpp
rclcpp_action
rclcpp_components
std_msgs
nav2_msgs
nav_2d_utils
Expand Down Expand Up @@ -75,6 +77,8 @@ ament_target_dependencies(${executable_name}

target_link_libraries(${executable_name} ${library_name})

rclcpp_components_register_nodes(${library_name} "nav2_controller::ControllerServer")

install(TARGETS simple_progress_checker simple_goal_checker stopped_goal_checker ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand Down
7 changes: 7 additions & 0 deletions nav2_controller/src/nav2_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -580,3 +580,10 @@ void ControllerServer::speedLimitCallback(const nav2_msgs::msg::SpeedLimit::Shar
}

} // namespace nav2_controller

#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_controller::ControllerServer)
4 changes: 4 additions & 0 deletions nav2_lifecycle_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ find_package(nav2_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(std_srvs REQUIRED)
Expand Down Expand Up @@ -36,6 +37,7 @@ set(dependencies
rclcpp
rclcpp_action
rclcpp_lifecycle
rclcpp_components
std_msgs
std_srvs
tf2_geometry_msgs
Expand All @@ -58,6 +60,8 @@ ament_target_dependencies(lifecycle_manager
${dependencies}
)

rclcpp_components_register_nodes(${library_name} "nav2_lifecycle_manager::LifecycleManager")

install(TARGETS
${library_name}
ARCHIVE DESTINATION lib
Expand Down
7 changes: 7 additions & 0 deletions nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -375,3 +375,10 @@ LifecycleManager::message(const std::string & msg)
}

} // namespace nav2_lifecycle_manager

#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_lifecycle_manager::LifecycleManager)
5 changes: 5 additions & 0 deletions nav2_map_server/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ find_package(ament_cmake REQUIRED)
find_package(nav2_common REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(yaml_cpp_vendor REQUIRED)
Expand Down Expand Up @@ -61,6 +62,7 @@ set(map_io_dependencies
set(map_server_dependencies
rclcpp
rclcpp_lifecycle
rclcpp_components
nav_msgs
nav2_msgs
yaml_cpp_vendor
Expand Down Expand Up @@ -123,6 +125,9 @@ if(WIN32)
YAML_CPP_DLL)
endif()

rclcpp_components_register_nodes(${library_name} "nav2_map_server::MapSaver")
rclcpp_components_register_nodes(${library_name} "nav2_map_server::MapServer")

install(TARGETS
${library_name} ${map_io_library_name}
ARCHIVE DESTINATION lib
Expand Down
7 changes: 7 additions & 0 deletions nav2_map_server/src/map_saver/map_saver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -228,3 +228,10 @@ bool MapSaver::saveMapTopicToFile(
}

} // 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::MapSaver)
7 changes: 7 additions & 0 deletions nav2_map_server/src/map_server/map_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -235,3 +235,10 @@ void MapServer::updateMsgHeader()
}

} // 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::MapServer)
4 changes: 4 additions & 0 deletions nav2_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ find_package(nav2_common REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(std_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(nav2_util REQUIRED)
Expand All @@ -31,6 +32,7 @@ set(dependencies
rclcpp
rclcpp_action
rclcpp_lifecycle
rclcpp_components
std_msgs
visualization_msgs
nav2_util
Expand Down Expand Up @@ -62,6 +64,8 @@ ament_target_dependencies(${executable_name}
${dependencies}
)

rclcpp_components_register_nodes(${library_name} "nav2_planner::PlannerServer")

install(TARGETS ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand Down
7 changes: 7 additions & 0 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -511,3 +511,10 @@ PlannerServer::publishPlan(const nav_msgs::msg::Path & path)
}

} // namespace nav2_planner

#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_planner::PlannerServer)
5 changes: 4 additions & 1 deletion nav2_recoveries/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ find_package(nav2_common REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(std_msgs REQUIRED)
find_package(nav2_behavior_tree REQUIRED)
find_package(nav2_util REQUIRED)
Expand All @@ -31,6 +32,7 @@ set(dependencies
rclcpp
rclcpp_action
rclcpp_lifecycle
rclcpp_components
std_msgs
nav2_util
nav2_behavior_tree
Expand Down Expand Up @@ -72,7 +74,7 @@ ament_target_dependencies(nav2_wait_recovery
pluginlib_export_plugin_description_file(nav2_core recovery_plugin.xml)

# Library
add_library(${library_name}
add_library(${library_name} SHARED
src/recovery_server.cpp
)

Expand All @@ -91,6 +93,7 @@ ament_target_dependencies(${executable_name}
${dependencies}
)

rclcpp_components_register_nodes(${library_name} "recovery_server::RecoveryServer")

install(TARGETS ${library_name}
nav2_backup_recovery
Expand Down
7 changes: 7 additions & 0 deletions nav2_recoveries/src/recovery_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,3 +182,10 @@ RecoveryServer::on_shutdown(const rclcpp_lifecycle::State &)
}

} // end namespace recovery_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(recovery_server::RecoveryServer)
4 changes: 4 additions & 0 deletions nav2_waypoint_follower/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ find_package(nav2_common REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(nav2_util REQUIRED)
Expand Down Expand Up @@ -46,6 +47,7 @@ set(dependencies
rclcpp
rclcpp_action
rclcpp_lifecycle
rclcpp_components
nav_msgs
nav2_msgs
nav2_util
Expand Down Expand Up @@ -76,6 +78,8 @@ ament_target_dependencies(photo_at_waypoint ${dependencies})
add_library(input_at_waypoint SHARED plugins/input_at_waypoint.cpp)
ament_target_dependencies(input_at_waypoint ${dependencies})

rclcpp_components_register_nodes(${library_name} "nav2_waypoint_follower::WaypointFollower")

install(TARGETS ${library_name} wait_at_waypoint photo_at_waypoint input_at_waypoint
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand Down
7 changes: 7 additions & 0 deletions nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -306,3 +306,10 @@ WaypointFollower::goalResponseCallback(
}

} // namespace nav2_waypoint_follower

#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_waypoint_follower::WaypointFollower)

0 comments on commit 420a6ff

Please sign in to comment.