19 #include "std_msgs/msg/string.hpp"
21 #include "nav2_behavior_tree/plugins/action/goal_checker_selector_node.hpp"
23 #include "rclcpp/rclcpp.hpp"
25 namespace nav2_behavior_tree
28 using std::placeholders::_1;
31 const std::string & name,
32 const BT::NodeConfiguration & conf)
33 : BT::SyncActionNode(name, conf)
37 config().blackboard->template get<std::chrono::milliseconds>(
"bt_loop_duration");
40 void GoalCheckerSelector::initialize()
42 createROSInterfaces();
45 void GoalCheckerSelector::createROSInterfaces()
47 std::string topic_new;
48 getInput(
"topic_name", topic_new);
49 if (topic_new != topic_name_ || !goal_checker_selector_sub_) {
50 topic_name_ = topic_new;
51 node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>(
"node");
52 callback_group_ = node_->create_callback_group(
53 rclcpp::CallbackGroupType::MutuallyExclusive,
55 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
57 goal_checker_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
59 std::bind(&GoalCheckerSelector::callbackGoalCheckerSelect,
this, _1),
65 BT::NodeStatus GoalCheckerSelector::tick()
67 if (!BT::isStatusActive(status())) {
71 callback_group_executor_.spin_all(bt_loop_duration_);
78 if (last_selected_goal_checker_.empty()) {
79 std::string default_goal_checker;
80 getInput(
"default_goal_checker", default_goal_checker);
81 if (default_goal_checker.empty()) {
82 return BT::NodeStatus::FAILURE;
84 last_selected_goal_checker_ = default_goal_checker;
88 setOutput(
"selected_goal_checker", last_selected_goal_checker_);
90 return BT::NodeStatus::SUCCESS;
94 GoalCheckerSelector::callbackGoalCheckerSelect(
const std_msgs::msg::String::SharedPtr msg)
96 last_selected_goal_checker_ = msg->data;
101 #include "behaviortree_cpp/bt_factory.h"
102 BT_REGISTER_NODES(factory)
A QoS profile for latched, reliable topics with a history of 10 messages.
The GoalCheckerSelector behavior is used to switch the goal checker of the controller server....
GoalCheckerSelector(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::GoalCheckerSelector.