Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
speed_controller.hpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2020 Sarthak Mittal
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__SPEED_CONTROLLER_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__SPEED_CONTROLLER_HPP_
18 
19 #include <memory>
20 #include <string>
21 #include <vector>
22 #include <deque>
23 
24 #include "nav_msgs/msg/odometry.hpp"
25 #include "nav2_util/odometry_utils.hpp"
26 
27 #include "behaviortree_cpp_v3/decorator_node.h"
28 
29 namespace nav2_behavior_tree
30 {
31 
37 class SpeedController : public BT::DecoratorNode
38 {
39 public:
46  const std::string & name,
47  const BT::NodeConfiguration & conf);
48 
53  static BT::PortsList providedPorts()
54  {
55  return {
56  BT::InputPort<double>("min_rate", 0.1, "Minimum rate"),
57  BT::InputPort<double>("max_rate", 1.0, "Maximum rate"),
58  BT::InputPort<double>("min_speed", 0.0, "Minimum speed"),
59  BT::InputPort<double>("max_speed", 0.5, "Maximum speed"),
60  };
61  }
62 
63 private:
68  BT::NodeStatus tick() override;
69 
74  inline double getScaledRate(const double & speed)
75  {
76  return std::max(
77  std::min(
78  (((speed - min_speed_) / d_speed_) * d_rate_) + min_rate_,
79  max_rate_), min_rate_);
80  }
81 
85  inline void updatePeriod()
86  {
87  auto velocity = odom_smoother_->getTwist();
88  double speed = std::hypot(velocity.linear.x, velocity.linear.y);
89  double rate = getScaledRate(speed);
90  period_ = 1.0 / rate;
91  }
92 
93  rclcpp::Node::SharedPtr node_;
94 
95  // To keep track of time to reset
96  rclcpp::Time start_;
97 
98  // To get a smoothed velocity
99  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
100 
101  bool first_tick_;
102 
103  // Time period after which child node should be ticked
104  double period_;
105 
106  // Rates thresholds to tick child node
107  double min_rate_;
108  double max_rate_;
109  double d_rate_;
110 
111  // Speed thresholds
112  double min_speed_;
113  double max_speed_;
114  double d_speed_;
115 
116  // current goal
117  geometry_msgs::msg::PoseStamped goal_;
118  std::vector<geometry_msgs::msg::PoseStamped> goals_;
119 };
120 
121 } // namespace nav2_behavior_tree
122 
123 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__SPEED_CONTROLLER_HPP_
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.