18 #include "std_msgs/msg/string.hpp"
20 #include "nav2_behavior_tree/plugins/action/progress_checker_selector_node.hpp"
22 #include "rclcpp/rclcpp.hpp"
24 namespace nav2_behavior_tree
27 using std::placeholders::_1;
30 const std::string & name,
31 const BT::NodeConfiguration & conf)
32 : BT::SyncActionNode(name, conf)
36 config().blackboard->template get<std::chrono::milliseconds>(
"bt_loop_duration");
39 void ProgressCheckerSelector::initialize()
41 createROSInterfaces();
44 void ProgressCheckerSelector::createROSInterfaces()
46 std::string topic_new;
47 getInput(
"topic_name", topic_new);
48 if (topic_new != topic_name_ || !progress_checker_selector_sub_) {
49 topic_name_ = topic_new;
50 node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>(
"node");
51 callback_group_ = node_->create_callback_group(
52 rclcpp::CallbackGroupType::MutuallyExclusive,
54 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
56 progress_checker_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
58 std::bind(&ProgressCheckerSelector::callbackProgressCheckerSelect,
this, _1),
64 BT::NodeStatus ProgressCheckerSelector::tick()
66 if (!BT::isStatusActive(status())) {
70 callback_group_executor_.spin_all(bt_loop_duration_);
77 if (last_selected_progress_checker_.empty()) {
78 std::string default_progress_checker;
79 getInput(
"default_progress_checker", default_progress_checker);
80 if (default_progress_checker.empty()) {
81 return BT::NodeStatus::FAILURE;
83 last_selected_progress_checker_ = default_progress_checker;
87 setOutput(
"selected_progress_checker", last_selected_progress_checker_);
89 return BT::NodeStatus::SUCCESS;
93 ProgressCheckerSelector::callbackProgressCheckerSelect(
const std_msgs::msg::String::SharedPtr msg)
95 last_selected_progress_checker_ = msg->data;
100 #include "behaviortree_cpp/bt_factory.h"
101 BT_REGISTER_NODES(factory)
A QoS profile for latched, reliable topics with a history of 10 messages.
The ProgressCheckerSelector behavior is used to switch the progress checker of the controller server....
ProgressCheckerSelector(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ProgressCheckerSelector.