Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
speed_controller.cpp
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 #include <string>
17 #include <memory>
18 #include <vector>
19 #include "nav2_util/geometry_utils.hpp"
20 
21 #include "nav2_behavior_tree/plugins/decorator/speed_controller.hpp"
22 
23 namespace nav2_behavior_tree
24 {
25 
27  const std::string & name,
28  const BT::NodeConfiguration & conf)
29 : BT::DecoratorNode(name, conf),
30  first_tick_(false),
31  period_(1.0),
32  min_rate_(0.1),
33  max_rate_(1.0),
34  min_speed_(0.0),
35  max_speed_(0.5)
36 {
37  node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
38 
39  getInput("min_rate", min_rate_);
40  getInput("max_rate", max_rate_);
41  getInput("min_speed", min_speed_);
42  getInput("max_speed", max_speed_);
43 
44  if (min_rate_ <= 0.0 || max_rate_ <= 0.0) {
45  std::string err_msg = "SpeedController node cannot have rate <= 0.0";
46  RCLCPP_FATAL(node_->get_logger(), "%s", err_msg.c_str());
47  throw BT::BehaviorTreeException(err_msg);
48  }
49 
50  d_rate_ = max_rate_ - min_rate_;
51  d_speed_ = max_speed_ - min_speed_;
52 
53  std::string odom_topic;
54  node_->get_parameter_or("odom_topic", odom_topic, std::string("odom"));
55  odom_smoother_ = config().blackboard->get<std::shared_ptr<nav2_util::OdomSmoother>>(
56  "odom_smoother");
57 }
58 
59 inline BT::NodeStatus SpeedController::tick()
60 {
61  if (status() == BT::NodeStatus::IDLE) {
62  // Reset since we're starting a new iteration of
63  // the speed controller (moving from IDLE to RUNNING)
64  config().blackboard->get<std::vector<geometry_msgs::msg::PoseStamped>>("goals", goals_);
65  config().blackboard->get<geometry_msgs::msg::PoseStamped>("goal", goal_);
66  period_ = 1.0 / max_rate_;
67  start_ = node_->now();
68  first_tick_ = true;
69  }
70 
71  std::vector<geometry_msgs::msg::PoseStamped> current_goals;
72  config().blackboard->get<std::vector<geometry_msgs::msg::PoseStamped>>("goals", current_goals);
73  geometry_msgs::msg::PoseStamped current_goal;
74  config().blackboard->get<geometry_msgs::msg::PoseStamped>("goal", current_goal);
75 
76  if (goal_ != current_goal || goals_ != current_goals) {
77  // Reset state and set period to max since we have a new goal
78  period_ = 1.0 / max_rate_;
79  start_ = node_->now();
80  first_tick_ = true;
81  goal_ = current_goal;
82  goals_ = current_goals;
83  }
84 
85  setStatus(BT::NodeStatus::RUNNING);
86 
87  auto elapsed = node_->now() - start_;
88 
89  // The child gets ticked the first time through and any time the period has
90  // expired. In addition, once the child begins to run, it is ticked each time
91  // 'til completion
92  if (first_tick_ || (child_node_->status() == BT::NodeStatus::RUNNING) ||
93  elapsed.seconds() >= period_)
94  {
95  first_tick_ = false;
96 
97  // update period if the last period is exceeded
98  if (elapsed.seconds() >= period_) {
99  updatePeriod();
100  start_ = node_->now();
101  }
102 
103  const BT::NodeStatus child_state = child_node_->executeTick();
104 
105  switch (child_state) {
106  case BT::NodeStatus::RUNNING:
107  return BT::NodeStatus::RUNNING;
108 
109  case BT::NodeStatus::SUCCESS:
110  return BT::NodeStatus::SUCCESS;
111 
112  case BT::NodeStatus::FAILURE:
113  default:
114  return BT::NodeStatus::FAILURE;
115  }
116  }
117 
118  return status();
119 }
120 
121 } // namespace nav2_behavior_tree
122 
123 #include "behaviortree_cpp_v3/bt_factory.h"
124 BT_REGISTER_NODES(factory)
125 {
126  factory.registerNodeType<nav2_behavior_tree::SpeedController>("SpeedController");
127 }
A BT::DecoratorNode that ticks its child every at a rate proportional to the speed of the robot....
SpeedController(const std::string &name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::SpeedController.