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)
39 callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
42 void SmootherSelector::initialize()
44 createROSInterfaces();
47 void SmootherSelector::createROSInterfaces()
49 std::string topic_new;
50 getInput(
"topic_name", topic_new);
51 if (topic_new != topic_name_ || !smoother_selector_sub_) {
52 topic_name_ = topic_new;
53 node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>(
"node");
54 callback_group_ = node_->create_callback_group(
55 rclcpp::CallbackGroupType::MutuallyExclusive,
57 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
59 smoother_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
61 std::bind(&SmootherSelector::callbackSmootherSelect,
this, _1),
67 BT::NodeStatus SmootherSelector::tick()
69 if (!BT::isStatusActive(status())) {
73 callback_group_executor_.spin_some();
80 if (last_selected_smoother_.empty()) {
81 std::string default_smoother;
82 getInput(
"default_smoother", default_smoother);
83 if (default_smoother.empty()) {
84 return BT::NodeStatus::FAILURE;
86 last_selected_smoother_ = default_smoother;
90 setOutput(
"selected_smoother", last_selected_smoother_);
92 return BT::NodeStatus::SUCCESS;
96 SmootherSelector::callbackSmootherSelect(
const std_msgs::msg::String::SharedPtr msg)
98 last_selected_smoother_ = msg->data;
103 #include "behaviortree_cpp/bt_factory.h"
104 BT_REGISTER_NODES(factory)
A QoS profile for latched, reliable topics with a history of 10 messages.
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.