16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__GOAL_CHECKER_SELECTOR_NODE_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__GOAL_CHECKER_SELECTOR_NODE_HPP_
22 #include "std_msgs/msg/string.hpp"
24 #include "behaviortree_cpp/action_node.h"
26 #include "nav2_ros_common/lifecycle_node.hpp"
28 namespace nav2_behavior_tree
49 const std::string & xml_tag_name,
50 const BT::NodeConfiguration & conf);
59 BT::InputPort<std::string>(
60 "default_goal_checker",
61 "the default goal_checker to use if there is not any external topic message received."),
63 BT::InputPort<std::string>(
65 "goal_checker_selector",
66 "the input topic name to select the goal_checker"),
68 BT::OutputPort<std::string>(
69 "selected_goal_checker",
70 "Selected goal_checker by subscription")
82 void createROSInterfaces();
87 BT::NodeStatus tick()
override;
94 void callbackGoalCheckerSelect(
const std_msgs::msg::String::SharedPtr msg);
96 nav2::Subscription<std_msgs::msg::String>::SharedPtr goal_checker_selector_sub_;
98 std::string last_selected_goal_checker_;
100 nav2::LifecycleNode::SharedPtr node_;
101 rclcpp::CallbackGroup::SharedPtr callback_group_;
102 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
104 std::string topic_name_;
The GoalCheckerSelector behavior is used to switch the goal checker of the controller server....
static BT::PortsList providedPorts()
Creates list of BT ports.
GoalCheckerSelector(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::GoalCheckerSelector.