15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__PROGRESS_CHECKER_SELECTOR_NODE_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__PROGRESS_CHECKER_SELECTOR_NODE_HPP_
21 #include "std_msgs/msg/string.hpp"
23 #include "behaviortree_cpp/action_node.h"
25 #include "rclcpp/rclcpp.hpp"
27 namespace nav2_behavior_tree
48 const std::string & xml_tag_name,
49 const BT::NodeConfiguration & conf);
58 BT::InputPort<std::string>(
59 "default_progress_checker",
60 "the default progress_checker to use if there is not any external topic message received."),
62 BT::InputPort<std::string>(
64 "progress_checker_selector",
65 "the input topic name to select the progress_checker"),
67 BT::OutputPort<std::string>(
68 "selected_progress_checker",
69 "Selected progress_checker by subscription")
81 void createROSInterfaces();
86 BT::NodeStatus tick()
override;
93 void callbackProgressCheckerSelect(
const std_msgs::msg::String::SharedPtr msg);
95 rclcpp::Subscription<std_msgs::msg::String>::SharedPtr progress_checker_selector_sub_;
97 std::string last_selected_progress_checker_;
99 rclcpp::Node::SharedPtr node_;
101 std::string topic_name_;
The ProgressCheckerSelector behavior is used to switch the progress checker of the controller server....
static BT::PortsList providedPorts()
Creates list of BT ports.
ProgressCheckerSelector(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ProgressCheckerSelector.