Skip to content

Commit

Permalink
behavior_tree: removed list of plugins from yaml
Browse files Browse the repository at this point in the history
Signed-off-by: Davide Faconti <[email protected]>
  • Loading branch information
facontidavide committed Feb 19, 2024
1 parent a6bcb34 commit c8b4eb5
Show file tree
Hide file tree
Showing 13 changed files with 60 additions and 463 deletions.
16 changes: 9 additions & 7 deletions nav2_behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -219,13 +219,16 @@ install(TARGETS ${library_name}
RUNTIME DESTINATION bin
)

# we will embed the list of plugin names inside a header file
set(GENERATED_DIR ${CMAKE_CURRENT_BINARY_DIR}/gen)
configure_file(plugins_list.hpp.in ${GENERATED_DIR}/plugins_list.hpp)

add_executable(generate_nav2_tree_nodes_xml src/generate_nav2_tree_nodes_xml.cpp)
ament_target_dependencies(generate_nav2_tree_nodes_xml ${dependencies})
# we will embed the list of plugin names inside a header file
configure_file(plugins_list.hpp.in ${CMAKE_CURRENT_BINARY_DIR}/gen/plugins_list.hpp)
target_include_directories(generate_nav2_tree_nodes_xml PRIVATE ${CMAKE_CURRENT_BINARY_DIR}/gen)
install(TARGETS generate_nav2_tree_nodes_xml
DESTINATION lib/${PROJECT_NAME} )
# allow generate_nav2_tree_nodes_xml to find plugins_list.hpp
target_include_directories(generate_nav2_tree_nodes_xml PRIVATE ${GENERATED_DIR})
install(TARGETS generate_nav2_tree_nodes_xml DESTINATION lib/${PROJECT_NAME})


install(DIRECTORY include/
DESTINATION include/
Expand All @@ -236,8 +239,7 @@ install(DIRECTORY test/utils/
)

install(FILES nav2_tree_nodes.xml DESTINATION share/${PROJECT_NAME})
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/gen/plugins_list.hpp DESTINATION include/${PROJECT_NAME})

install(FILES ${GENERATED_DIR}/plugins_list.hpp DESTINATION include/${PROJECT_NAME})

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
Expand Down
2 changes: 1 addition & 1 deletion nav2_behavior_tree/plugins_list.hpp.in
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,5 @@
// This was automativally generated by cmake
namespace nav2::details
{
const char* BT_PLUGIN_LIST = "@plugin_libs@";
const char* BT_BUILTIN_PLUGINS = "@plugin_libs@";
}
2 changes: 1 addition & 1 deletion nav2_behavior_tree/src/generate_nav2_tree_nodes_xml.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ int main()
BT::BehaviorTreeFactory factory;

std::vector<std::string> plugins_list;
boost::split(plugins_list, nav2::details::BT_PLUGIN_LIST, boost::is_any_of(";"));
boost::split(plugins_list, nav2::details::BT_BUILTIN_PLUGINS, boost::is_any_of(";"));

for (const auto & plugin : plugins_list) {
std::cout << "Loading: " << plugin << "\n";
Expand Down
57 changes: 5 additions & 52 deletions nav2_bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -56,58 +56,11 @@ bt_navigator:
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_compute_path_through_poses_action_bt_node
- nav2_smooth_path_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_assisted_teleop_action_bt_node
- nav2_back_up_action_bt_node
- nav2_drive_on_heading_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_globally_updated_goal_condition_bt_node
- nav2_is_path_valid_condition_bt_node
- nav2_are_error_codes_active_condition_bt_node
- nav2_would_a_controller_recovery_help_condition_bt_node
- nav2_would_a_planner_recovery_help_condition_bt_node
- nav2_would_a_smoother_recovery_help_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_truncate_path_action_bt_node
- nav2_truncate_path_local_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_path_expiring_timer_condition
- nav2_distance_traveled_condition_bt_node
- nav2_single_trigger_bt_node
- nav2_goal_updated_controller_bt_node
- nav2_is_battery_low_condition_bt_node
- nav2_navigate_through_poses_action_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_remove_passed_goals_action_bt_node
- nav2_planner_selector_bt_node
- nav2_controller_selector_bt_node
- nav2_goal_checker_selector_bt_node
- nav2_controller_cancel_bt_node
- nav2_path_longer_on_approach_bt_node
- nav2_wait_cancel_bt_node
- nav2_spin_cancel_bt_node
- nav2_back_up_cancel_bt_node
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node

# plugin_lib_names is used to add custom BT plugins to the executor (vector of strings).
# Built-in plugins are added automatically
plugin_lib_names: []

error_code_names:
- compute_path_error_code
- follow_path_error_code
Expand Down
57 changes: 5 additions & 52 deletions nav2_bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -56,58 +56,11 @@ bt_navigator:
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_compute_path_through_poses_action_bt_node
- nav2_smooth_path_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_assisted_teleop_action_bt_node
- nav2_back_up_action_bt_node
- nav2_drive_on_heading_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_globally_updated_goal_condition_bt_node
- nav2_is_path_valid_condition_bt_node
- nav2_are_error_codes_active_condition_bt_node
- nav2_would_a_controller_recovery_help_condition_bt_node
- nav2_would_a_planner_recovery_help_condition_bt_node
- nav2_would_a_smoother_recovery_help_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_truncate_path_action_bt_node
- nav2_truncate_path_local_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_path_expiring_timer_condition
- nav2_distance_traveled_condition_bt_node
- nav2_single_trigger_bt_node
- nav2_goal_updated_controller_bt_node
- nav2_is_battery_low_condition_bt_node
- nav2_navigate_through_poses_action_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_remove_passed_goals_action_bt_node
- nav2_planner_selector_bt_node
- nav2_controller_selector_bt_node
- nav2_goal_checker_selector_bt_node
- nav2_controller_cancel_bt_node
- nav2_path_longer_on_approach_bt_node
- nav2_wait_cancel_bt_node
- nav2_spin_cancel_bt_node
- nav2_back_up_cancel_bt_node
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node

# plugin_lib_names is used to add custom BT plugins to the executor (vector of strings).
# Built-in plugins are added automatically
plugin_lib_names: []

error_code_names:
- compute_path_error_code
- follow_path_error_code
Expand Down
57 changes: 5 additions & 52 deletions nav2_bringup/params/nav2_multirobot_params_all.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -56,58 +56,11 @@ bt_navigator:
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_compute_path_through_poses_action_bt_node
- nav2_smooth_path_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_assisted_teleop_action_bt_node
- nav2_back_up_action_bt_node
- nav2_drive_on_heading_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_globally_updated_goal_condition_bt_node
- nav2_is_path_valid_condition_bt_node
- nav2_are_error_codes_active_condition_bt_node
- nav2_would_a_controller_recovery_help_condition_bt_node
- nav2_would_a_planner_recovery_help_condition_bt_node
- nav2_would_a_smoother_recovery_help_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_truncate_path_action_bt_node
- nav2_truncate_path_local_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_path_expiring_timer_condition
- nav2_distance_traveled_condition_bt_node
- nav2_single_trigger_bt_node
- nav2_goal_updated_controller_bt_node
- nav2_is_battery_low_condition_bt_node
- nav2_navigate_through_poses_action_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_remove_passed_goals_action_bt_node
- nav2_planner_selector_bt_node
- nav2_controller_selector_bt_node
- nav2_goal_checker_selector_bt_node
- nav2_controller_cancel_bt_node
- nav2_path_longer_on_approach_bt_node
- nav2_wait_cancel_bt_node
- nav2_spin_cancel_bt_node
- nav2_back_up_cancel_bt_node
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node

# plugin_lib_names is used to add custom BT plugins to the executor (vector of strings).
# Built-in plugins are added automatically
plugin_lib_names: []

error_code_names:
- compute_path_error_code
- follow_path_error_code
Expand Down
57 changes: 5 additions & 52 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -56,58 +56,11 @@ bt_navigator:
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_compute_path_through_poses_action_bt_node
- nav2_smooth_path_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_assisted_teleop_action_bt_node
- nav2_back_up_action_bt_node
- nav2_drive_on_heading_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_globally_updated_goal_condition_bt_node
- nav2_is_path_valid_condition_bt_node
- nav2_are_error_codes_active_condition_bt_node
- nav2_would_a_controller_recovery_help_condition_bt_node
- nav2_would_a_planner_recovery_help_condition_bt_node
- nav2_would_a_smoother_recovery_help_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_truncate_path_action_bt_node
- nav2_truncate_path_local_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_path_expiring_timer_condition
- nav2_distance_traveled_condition_bt_node
- nav2_single_trigger_bt_node
- nav2_goal_updated_controller_bt_node
- nav2_is_battery_low_condition_bt_node
- nav2_navigate_through_poses_action_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_remove_passed_goals_action_bt_node
- nav2_planner_selector_bt_node
- nav2_controller_selector_bt_node
- nav2_goal_checker_selector_bt_node
- nav2_controller_cancel_bt_node
- nav2_path_longer_on_approach_bt_node
- nav2_wait_cancel_bt_node
- nav2_spin_cancel_bt_node
- nav2_back_up_cancel_bt_node
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node

# plugin_lib_names is used to add custom BT plugins to the executor (vector of strings).
# Built-in plugins are added automatically
plugin_lib_names: []

error_code_names:
- compute_path_error_code
- follow_path_error_code
Expand Down
67 changes: 11 additions & 56 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,15 @@
#include <string>
#include <utility>
#include <vector>
#include <boost/algorithm/string.hpp>

#include "nav2_util/geometry_utils.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/robot_utils.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

#include "nav2_behavior_tree/plugins_list.hpp"

using nav2_util::declare_parameter_if_not_declared;

namespace nav2_bt_navigator
Expand All @@ -36,62 +39,8 @@ BtNavigator::BtNavigator(rclcpp::NodeOptions options)
{
RCLCPP_INFO(get_logger(), "Creating");

const std::vector<std::string> plugin_libs = {
"nav2_compute_path_to_pose_action_bt_node",
"nav2_compute_path_through_poses_action_bt_node",
"nav2_smooth_path_action_bt_node",
"nav2_follow_path_action_bt_node",
"nav2_spin_action_bt_node",
"nav2_wait_action_bt_node",
"nav2_assisted_teleop_action_bt_node",
"nav2_back_up_action_bt_node",
"nav2_drive_on_heading_bt_node",
"nav2_clear_costmap_service_bt_node",
"nav2_is_stuck_condition_bt_node",
"nav2_goal_reached_condition_bt_node",
"nav2_initial_pose_received_condition_bt_node",
"nav2_goal_updated_condition_bt_node",
"nav2_globally_updated_goal_condition_bt_node",
"nav2_is_path_valid_condition_bt_node",
"nav2_are_error_codes_active_condition_bt_node",
"nav2_would_a_controller_recovery_help_condition_bt_node",
"nav2_would_a_planner_recovery_help_condition_bt_node",
"nav2_would_a_smoother_recovery_help_condition_bt_node",
"nav2_reinitialize_global_localization_service_bt_node",
"nav2_rate_controller_bt_node",
"nav2_distance_controller_bt_node",
"nav2_speed_controller_bt_node",
"nav2_truncate_path_action_bt_node",
"nav2_truncate_path_local_action_bt_node",
"nav2_goal_updater_node_bt_node",
"nav2_recovery_node_bt_node",
"nav2_pipeline_sequence_bt_node",
"nav2_round_robin_node_bt_node",
"nav2_transform_available_condition_bt_node",
"nav2_time_expired_condition_bt_node",
"nav2_path_expiring_timer_condition",
"nav2_distance_traveled_condition_bt_node",
"nav2_single_trigger_bt_node",
"nav2_goal_updated_controller_bt_node",
"nav2_is_battery_low_condition_bt_node",
"nav2_navigate_through_poses_action_bt_node",
"nav2_navigate_to_pose_action_bt_node",
"nav2_remove_passed_goals_action_bt_node",
"nav2_planner_selector_bt_node",
"nav2_controller_selector_bt_node",
"nav2_goal_checker_selector_bt_node",
"nav2_controller_cancel_bt_node",
"nav2_path_longer_on_approach_bt_node",
"nav2_wait_cancel_bt_node",
"nav2_spin_cancel_bt_node",
"nav2_assisted_teleop_cancel_bt_node",
"nav2_back_up_cancel_bt_node",
"nav2_drive_on_heading_cancel_bt_node",
"nav2_is_battery_charging_condition_bt_node"
};

declare_parameter_if_not_declared(
this, "plugin_lib_names", rclcpp::ParameterValue(plugin_libs));
this, "plugin_lib_names", rclcpp::ParameterValue(std::vector<std::string>{}));
declare_parameter_if_not_declared(
this, "transform_tolerance", rclcpp::ParameterValue(0.1));
declare_parameter_if_not_declared(
Expand Down Expand Up @@ -124,7 +73,13 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
odom_topic_ = get_parameter("odom_topic").as_string();

// Libraries to pull plugins (BT Nodes) from
auto plugin_lib_names = get_parameter("plugin_lib_names").as_string_array();
std::vector<std::string> plugin_lib_names;
boost::split(plugin_lib_names, nav2::details::BT_BUILTIN_PLUGINS, boost::is_any_of(";"));
auto user_defined_plugins = get_parameter("plugin_lib_names").as_string_array();
// append user_defined_plugins to plugin_lib_names
plugin_lib_names.insert(
plugin_lib_names.end(), user_defined_plugins.begin(),
user_defined_plugins.end());

nav2_core::FeedbackUtils feedback_utils;
feedback_utils.tf = tf_;
Expand Down
Loading

0 comments on commit c8b4eb5

Please sign in to comment.