16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__SPEED_CONTROLLER_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__SPEED_CONTROLLER_HPP_
24 #include "behaviortree_cpp/decorator_node.h"
25 #include "behaviortree_cpp/json_export.h"
26 #include "nav_msgs/msg/odometry.hpp"
27 #include "nav2_util/odometry_utils.hpp"
28 #include "nav2_behavior_tree/bt_utils.hpp"
29 #include "nav2_behavior_tree/json_utils.hpp"
32 namespace nav2_behavior_tree
51 const std::string & name,
52 const BT::NodeConfiguration & conf);
61 BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
62 BT::RegisterJsonDefinition<nav_msgs::msg::Goals>();
65 BT::InputPort<double>(
"min_rate", 0.1,
"Minimum rate"),
66 BT::InputPort<double>(
"max_rate", 1.0,
"Maximum rate"),
67 BT::InputPort<double>(
"min_speed", 0.0,
"Minimum speed"),
68 BT::InputPort<double>(
"max_speed", 0.5,
"Maximum speed"),
69 BT::InputPort<nav_msgs::msg::Goals>(
70 "goals",
"Vector of navigation goals"),
71 BT::InputPort<geometry_msgs::msg::PoseStamped>(
72 "goal",
"Navigation goal"),
81 BT::NodeStatus tick()
override;
87 inline double getScaledRate(
const double & speed)
91 (((speed - min_speed_) / d_speed_) * d_rate_) + min_rate_,
92 max_rate_), min_rate_);
98 inline void updatePeriod()
100 auto velocity = odom_smoother_->getTwist();
101 double speed = std::hypot(velocity.linear.x, velocity.linear.y);
102 double rate = getScaledRate(speed);
103 period_ = 1.0 / rate;
106 nav2::LifecycleNode::SharedPtr node_;
112 std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
130 geometry_msgs::msg::PoseStamped goal_;
131 nav_msgs::msg::Goals 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.