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<nav2::LifecycleNode::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 odom_smoother_ = config().blackboard->get<std::shared_ptr<nav2_util::OdomSmoother>>(
57 inline BT::NodeStatus SpeedController::tick()
59 if (!BT::isStatusActive(status())) {
62 BT::getInputOrBlackboard(
"goals", goals_);
63 BT::getInputOrBlackboard(
"goal", goal_);
64 period_ = 1.0 / max_rate_;
65 start_ = node_->now();
69 nav_msgs::msg::Goals current_goals;
70 BT::getInputOrBlackboard(
"goals", current_goals);
71 geometry_msgs::msg::PoseStamped current_goal;
72 BT::getInputOrBlackboard(
"goal", current_goal);
74 if (goal_ != current_goal || goals_ != current_goals) {
76 period_ = 1.0 / max_rate_;
77 start_ = node_->now();
80 goals_ = current_goals;
83 setStatus(BT::NodeStatus::RUNNING);
85 auto elapsed = node_->now() - start_;
90 if (first_tick_ || (child_node_->status() == BT::NodeStatus::RUNNING) ||
91 elapsed.seconds() >= period_)
96 if (elapsed.seconds() >= period_) {
98 start_ = node_->now();
101 return child_node_->executeTick();
109 #include "behaviortree_cpp/bt_factory.h"
110 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.