Nav2 Navigation Stack - jazzy  jazzy
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/decorator_node.h"
28 #include "nav2_behavior_tree/bt_utils.hpp"
29 
30 namespace nav2_behavior_tree
31 {
32 
38 class SpeedController : public BT::DecoratorNode
39 {
40 public:
47  const std::string & name,
48  const BT::NodeConfiguration & conf);
49 
54  static BT::PortsList providedPorts()
55  {
56  return {
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"),
65  };
66  }
67 
68 private:
73  BT::NodeStatus tick() override;
74 
79  inline double getScaledRate(const double & speed)
80  {
81  return std::max(
82  std::min(
83  (((speed - min_speed_) / d_speed_) * d_rate_) + min_rate_,
84  max_rate_), min_rate_);
85  }
86 
90  inline void updatePeriod()
91  {
92  auto velocity = odom_smoother_->getTwist();
93  double speed = std::hypot(velocity.linear.x, velocity.linear.y);
94  double rate = getScaledRate(speed);
95  period_ = 1.0 / rate;
96  }
97 
98  rclcpp::Node::SharedPtr node_;
99 
100  // To keep track of time to reset
101  rclcpp::Time start_;
102 
103  // To get a smoothed velocity
104  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
105 
106  bool first_tick_;
107 
108  // Time period after which child node should be ticked
109  double period_;
110 
111  // Rates thresholds to tick child node
112  double min_rate_;
113  double max_rate_;
114  double d_rate_;
115 
116  // Speed thresholds
117  double min_speed_;
118  double max_speed_;
119  double d_speed_;
120 
121  // current goal
122  geometry_msgs::msg::PoseStamped goal_;
123  std::vector<geometry_msgs::msg::PoseStamped> goals_;
124 };
125 
126 } // namespace nav2_behavior_tree
127 
128 #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.