20 #include "std_msgs/msg/string.hpp"
22 #include "nav2_behavior_tree/plugins/action/smoother_selector_node.hpp"
24 #include "rclcpp/rclcpp.hpp"
26 namespace nav2_behavior_tree
29 using std::placeholders::_1;
32 const std::string & name,
33 const BT::NodeConfiguration & conf)
34 : BT::SyncActionNode(name, conf)
36 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
37 callback_group_ = node_->create_callback_group(
38 rclcpp::CallbackGroupType::MutuallyExclusive,
40 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
42 getInput(
"topic_name", topic_name_);
44 rclcpp::QoS qos(rclcpp::KeepLast(1));
45 qos.transient_local().reliable();
47 rclcpp::SubscriptionOptions sub_option;
48 sub_option.callback_group = callback_group_;
49 smoother_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
52 std::bind(&SmootherSelector::callbackSmootherSelect,
this, _1),
56 BT::NodeStatus SmootherSelector::tick()
58 callback_group_executor_.spin_some();
65 if (last_selected_smoother_.empty()) {
66 std::string default_smoother;
67 getInput(
"default_smoother", default_smoother);
68 if (default_smoother.empty()) {
69 return BT::NodeStatus::FAILURE;
71 last_selected_smoother_ = default_smoother;
75 setOutput(
"selected_smoother", last_selected_smoother_);
77 return BT::NodeStatus::SUCCESS;
81 SmootherSelector::callbackSmootherSelect(
const std_msgs::msg::String::SharedPtr msg)
83 last_selected_smoother_ = msg->data;
88 #include "behaviortree_cpp_v3/bt_factory.h"
89 BT_REGISTER_NODES(factory)
The SmootherSelector behavior is used to switch the smoother that will be used by the smoother server...
SmootherSelector(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::SmootherSelector.