Skip to content

Commit

Permalink
Add generate_nav2_tree_nodes_xml
Browse files Browse the repository at this point in the history
Signed-off-by: Davide Faconti <[email protected]>
  • Loading branch information
facontidavide committed Jan 26, 2024
1 parent a8a0c3a commit a6bcb34
Show file tree
Hide file tree
Showing 4 changed files with 69 additions and 52 deletions.
10 changes: 10 additions & 0 deletions nav2_behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -219,6 +219,14 @@ install(TARGETS ${library_name}
RUNTIME DESTINATION bin
)

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} )

install(DIRECTORY include/
DESTINATION include/
)
Expand All @@ -228,6 +236,8 @@ 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})


if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
Expand Down
6 changes: 6 additions & 0 deletions nav2_behavior_tree/plugins_list.hpp.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@

// This was automativally generated by cmake
namespace nav2::details
{
const char* BT_PLUGIN_LIST = "@plugin_libs@";
}
47 changes: 47 additions & 0 deletions nav2_behavior_tree/src/generate_nav2_tree_nodes_xml.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
// Copyright (c) 2024 Davide Faconti
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License. Reserved.

#include <vector>
#include <string>
#include <fstream>
#include <boost/algorithm/string.hpp>

#include "behaviortree_cpp_v3/behavior_tree.h"
#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp_v3/utils/shared_library.h"
#include "behaviortree_cpp_v3/xml_parsing.h"

#include "plugins_list.hpp"

int main()
{
BT::BehaviorTreeFactory factory;

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

for (const auto & plugin : plugins_list) {
std::cout << "Loading: " << plugin << "\n";
factory.registerFromPlugin(BT::SharedLibrary::getOSName(plugin));
}
std::cout << "\nGenerating file: nav2_tree_nodes.xml\n"
<< "\nCompare it with the one in the git repo and update the latter if necessary.\n";

std::ofstream xml_file;
xml_file.open("nav2_tree_nodes.xml");
xml_file << BT::writeTreeNodesModelXML(factory) << std::endl;
xml_file.close();

return 0;
}
58 changes: 6 additions & 52 deletions nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include <fstream>
#include <memory>
#include <utility>
#include <boost/algorithm/string.hpp>
#include <boost/filesystem.hpp>

#include "gtest/gtest.h"
Expand All @@ -31,6 +32,8 @@

#include "nav2_util/odometry_utils.hpp"

#include "nav2_behavior_tree/plugins_list.hpp"

#include "rclcpp/rclcpp.hpp"
#include "ament_index_cpp/get_package_share_directory.hpp"

Expand Down Expand Up @@ -58,58 +61,9 @@ class BehaviorTreeHandler

odom_smoother_ = std::make_shared<nav2_util::OdomSmoother>(node_);

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_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_assisted_teleop_cancel_bt_node",
"nav2_wait_cancel_bt_node",
"nav2_spin_cancel_bt_node",
"nav2_back_up_cancel_bt_node",
"nav2_drive_on_heading_cancel_bt_node",
"nav2_goal_updated_controller_bt_node"
};
std::vector<std::string> plugin_libs;
boost::split(plugin_libs, nav2::details::BT_PLUGIN_LIST, boost::is_any_of(";"));

for (const auto & p : plugin_libs) {
factory_.registerFromPlugin(BT::SharedLibrary::getOSName(p));
}
Expand Down

0 comments on commit a6bcb34

Please sign in to comment.