Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
rate_controller.cpp
1 // Copyright (c) 2018 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <chrono>
16 #include <string>
17 
18 #include "nav2_behavior_tree/plugins/decorator/rate_controller.hpp"
19 
20 namespace nav2_behavior_tree
21 {
22 
24  const std::string & name,
25  const BT::NodeConfiguration & conf)
26 : BT::DecoratorNode(name, conf),
27  first_time_(false)
28 {
29 }
30 
32 {
33  double hz = 1.0;
34  getInput("hz", hz);
35  period_ = 1.0 / hz;
36 }
37 
38 BT::NodeStatus RateController::tick()
39 {
40  if (!BT::isStatusActive(status())) {
41  initialize();
42  }
43 
44  if (!BT::isStatusActive(status())) {
45  // Reset the starting point since we're starting a new iteration of
46  // the rate controller (moving from IDLE to RUNNING)
47  start_ = std::chrono::high_resolution_clock::now();
48  first_time_ = true;
49  }
50 
51  setStatus(BT::NodeStatus::RUNNING);
52 
53  // Determine how long its been since we've started this iteration
54  auto now = std::chrono::high_resolution_clock::now();
55  auto elapsed = now - start_;
56 
57  // Now, get that in seconds
58  typedef std::chrono::duration<float> float_seconds;
59  auto seconds = std::chrono::duration_cast<float_seconds>(elapsed);
60 
61  // The child gets ticked the first time through and any time the period has
62  // expired. In addition, once the child begins to run, it is ticked each time
63  // 'til completion
64  if (first_time_ || (child_node_->status() == BT::NodeStatus::RUNNING) ||
65  seconds.count() >= period_)
66  {
67  first_time_ = false;
68  const BT::NodeStatus child_state = child_node_->executeTick();
69 
70  switch (child_state) {
71  case BT::NodeStatus::SKIPPED:
72  case BT::NodeStatus::RUNNING:
73  case BT::NodeStatus::FAILURE:
74  return child_state;
75 
76  case BT::NodeStatus::SUCCESS:
77  start_ = std::chrono::high_resolution_clock::now(); // Reset the timer
78  return BT::NodeStatus::SUCCESS;
79 
80  default:
81  return BT::NodeStatus::FAILURE;
82  }
83  }
84 
85  return status();
86 }
87 
88 } // namespace nav2_behavior_tree
89 
90 #include "behaviortree_cpp/bt_factory.h"
91 BT_REGISTER_NODES(factory)
92 {
93  factory.registerNodeType<nav2_behavior_tree::RateController>("RateController");
94 }
A BT::DecoratorNode that ticks its child at a specified rate.
void initialize()
Function to read parameters and initialize class variables.
RateController(const std::string &name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::RateController.