Nav2 Navigation Stack - kilted  kilted
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 "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"
30 
31 
32 namespace nav2_behavior_tree
33 {
34 
42 class SpeedController : public BT::DecoratorNode
43 {
44 public:
51  const std::string & name,
52  const BT::NodeConfiguration & conf);
53 
58  static BT::PortsList providedPorts()
59  {
60  // Register JSON definitions for the types used in the ports
61  BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
62  BT::RegisterJsonDefinition<nav_msgs::msg::Goals>();
63 
64  return {
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"),
73  };
74  }
75 
76 private:
81  BT::NodeStatus tick() override;
82 
87  inline double getScaledRate(const double & speed)
88  {
89  return std::max(
90  std::min(
91  (((speed - min_speed_) / d_speed_) * d_rate_) + min_rate_,
92  max_rate_), min_rate_);
93  }
94 
98  inline void updatePeriod()
99  {
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;
104  }
105 
106  rclcpp::Node::SharedPtr node_;
107 
108  // To keep track of time to reset
109  rclcpp::Time start_;
110 
111  // To get a smoothed velocity
112  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
113 
114  bool first_tick_;
115 
116  // Time period after which child node should be ticked
117  double period_;
118 
119  // Rates thresholds to tick child node
120  double min_rate_;
121  double max_rate_;
122  double d_rate_;
123 
124  // Speed thresholds
125  double min_speed_;
126  double max_speed_;
127  double d_speed_;
128 
129  // current goal
130  geometry_msgs::msg::PoseStamped goal_;
131  nav_msgs::msg::Goals goals_;
132 };
133 
134 } // namespace nav2_behavior_tree
135 
136 #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.