19 #include "nav2_util/geometry_utils.hpp"
21 #include "nav2_behavior_tree/plugins/decorator/speed_controller.hpp"
23 namespace nav2_behavior_tree
27 const std::string & name,
28 const BT::NodeConfiguration & conf)
29 : BT::DecoratorNode(name, conf),
37 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
39 getInput(
"min_rate", min_rate_);
40 getInput(
"max_rate", max_rate_);
41 getInput(
"min_speed", min_speed_);
42 getInput(
"max_speed", max_speed_);
44 if (min_rate_ <= 0.0 || max_rate_ <= 0.0) {
45 std::string err_msg =
"SpeedController node cannot have rate <= 0.0";
46 RCLCPP_FATAL(node_->get_logger(),
"%s", err_msg.c_str());
47 throw BT::BehaviorTreeException(err_msg);
50 d_rate_ = max_rate_ - min_rate_;
51 d_speed_ = max_speed_ - min_speed_;
53 std::string odom_topic;
54 node_->get_parameter_or(
"odom_topic", odom_topic, std::string(
"odom"));
55 odom_smoother_ = config().blackboard->get<std::shared_ptr<nav2_util::OdomSmoother>>(
59 inline BT::NodeStatus SpeedController::tick()
61 if (status() == BT::NodeStatus::IDLE) {
64 config().blackboard->get<std::vector<geometry_msgs::msg::PoseStamped>>(
"goals", goals_);
65 config().blackboard->get<geometry_msgs::msg::PoseStamped>(
"goal", goal_);
66 period_ = 1.0 / max_rate_;
67 start_ = node_->now();
71 std::vector<geometry_msgs::msg::PoseStamped> current_goals;
72 config().blackboard->get<std::vector<geometry_msgs::msg::PoseStamped>>(
"goals", current_goals);
73 geometry_msgs::msg::PoseStamped current_goal;
74 config().blackboard->get<geometry_msgs::msg::PoseStamped>(
"goal", current_goal);
76 if (goal_ != current_goal || goals_ != current_goals) {
78 period_ = 1.0 / max_rate_;
79 start_ = node_->now();
82 goals_ = current_goals;
85 setStatus(BT::NodeStatus::RUNNING);
87 auto elapsed = node_->now() - start_;
92 if (first_tick_ || (child_node_->status() == BT::NodeStatus::RUNNING) ||
93 elapsed.seconds() >= period_)
98 if (elapsed.seconds() >= period_) {
100 start_ = node_->now();
103 const BT::NodeStatus child_state = child_node_->executeTick();
105 switch (child_state) {
106 case BT::NodeStatus::RUNNING:
107 return BT::NodeStatus::RUNNING;
109 case BT::NodeStatus::SUCCESS:
110 return BT::NodeStatus::SUCCESS;
112 case BT::NodeStatus::FAILURE:
114 return BT::NodeStatus::FAILURE;
123 #include "behaviortree_cpp_v3/bt_factory.h"
124 BT_REGISTER_NODES(factory)
A BT::DecoratorNode that ticks its child every at a rate proportional to the speed of the robot....
SpeedController(const std::string &name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::SpeedController.