Nav2 Navigation Stack - rolling  main
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<nav2::LifecycleNode::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  odom_smoother_ = config().blackboard->get<std::shared_ptr<nav2_util::OdomSmoother>>(
54  "odom_smoother");
55 }
56 
57 inline BT::NodeStatus SpeedController::tick()
58 {
59  if (!BT::isStatusActive(status())) {
60  // Reset since we're starting a new iteration of
61  // the speed controller (moving from IDLE to RUNNING)
62  BT::getInputOrBlackboard("goals", goals_);
63  BT::getInputOrBlackboard("goal", goal_);
64  period_ = 1.0 / max_rate_;
65  start_ = node_->now();
66  first_tick_ = true;
67  }
68 
69  nav_msgs::msg::Goals current_goals;
70  BT::getInputOrBlackboard("goals", current_goals);
71  geometry_msgs::msg::PoseStamped current_goal;
72  BT::getInputOrBlackboard("goal", current_goal);
73 
74  if (goal_ != current_goal || goals_ != current_goals) {
75  // Reset state and set period to max since we have a new goal
76  period_ = 1.0 / max_rate_;
77  start_ = node_->now();
78  first_tick_ = true;
79  goal_ = current_goal;
80  goals_ = current_goals;
81  }
82 
83  setStatus(BT::NodeStatus::RUNNING);
84 
85  auto elapsed = node_->now() - start_;
86 
87  // The child gets ticked the first time through and any time the period has
88  // expired. In addition, once the child begins to run, it is ticked each time
89  // 'til completion
90  if (first_tick_ || (child_node_->status() == BT::NodeStatus::RUNNING) ||
91  elapsed.seconds() >= period_)
92  {
93  first_tick_ = false;
94 
95  // update period if the last period is exceeded
96  if (elapsed.seconds() >= period_) {
97  updatePeriod();
98  start_ = node_->now();
99  }
100 
101  return child_node_->executeTick();
102  }
103 
104  return status();
105 }
106 
107 } // namespace nav2_behavior_tree
108 
109 #include "behaviortree_cpp/bt_factory.h"
110 BT_REGISTER_NODES(factory)
111 {
112  factory.registerNodeType<nav2_behavior_tree::SpeedController>("SpeedController");
113 }
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.