16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__SPEED_CONTROLLER_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__SPEED_CONTROLLER_HPP_
24 #include "nav_msgs/msg/odometry.hpp"
25 #include "nav2_util/odometry_utils.hpp"
27 #include "behaviortree_cpp/decorator_node.h"
28 #include "nav2_behavior_tree/bt_utils.hpp"
30 namespace nav2_behavior_tree
47 const std::string & name,
48 const BT::NodeConfiguration & conf);
57 BT::InputPort<double>(
"min_rate", 0.1,
"Minimum rate"),
58 BT::InputPort<double>(
"max_rate", 1.0,
"Maximum rate"),
59 BT::InputPort<double>(
"min_speed", 0.0,
"Minimum speed"),
60 BT::InputPort<double>(
"max_speed", 0.5,
"Maximum speed"),
61 BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
62 "goals",
"Vector of navigation goals"),
63 BT::InputPort<geometry_msgs::msg::PoseStamped>(
64 "goal",
"Navigation goal"),
73 BT::NodeStatus tick()
override;
79 inline double getScaledRate(
const double & speed)
83 (((speed - min_speed_) / d_speed_) * d_rate_) + min_rate_,
84 max_rate_), min_rate_);
90 inline void updatePeriod()
92 auto velocity = odom_smoother_->getTwist();
93 double speed = std::hypot(velocity.linear.x, velocity.linear.y);
94 double rate = getScaledRate(speed);
98 rclcpp::Node::SharedPtr node_;
104 std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
122 geometry_msgs::msg::PoseStamped goal_;
123 std::vector<geometry_msgs::msg::PoseStamped> goals_;
A BT::DecoratorNode that ticks its child every at a rate proportional to the speed of the robot....
static BT::PortsList providedPorts()
Creates list of BT ports.
SpeedController(const std::string &name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::SpeedController.