Nav2 Navigation Stack - humble  humble
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  double hz = 1.0;
30  getInput("hz", hz);
31  period_ = 1.0 / hz;
32 }
33 
34 BT::NodeStatus RateController::tick()
35 {
36  if (status() == BT::NodeStatus::IDLE) {
37  // Reset the starting point since we're starting a new iteration of
38  // the rate controller (moving from IDLE to RUNNING)
39  start_ = std::chrono::high_resolution_clock::now();
40  first_time_ = true;
41  }
42 
43  setStatus(BT::NodeStatus::RUNNING);
44 
45  // Determine how long its been since we've started this iteration
46  auto now = std::chrono::high_resolution_clock::now();
47  auto elapsed = now - start_;
48 
49  // Now, get that in seconds
50  typedef std::chrono::duration<float> float_seconds;
51  auto seconds = std::chrono::duration_cast<float_seconds>(elapsed);
52 
53  // The child gets ticked the first time through and any time the period has
54  // expired. In addition, once the child begins to run, it is ticked each time
55  // 'til completion
56  if (first_time_ || (child_node_->status() == BT::NodeStatus::RUNNING) ||
57  seconds.count() >= period_)
58  {
59  first_time_ = false;
60  const BT::NodeStatus child_state = child_node_->executeTick();
61 
62  switch (child_state) {
63  case BT::NodeStatus::RUNNING:
64  return BT::NodeStatus::RUNNING;
65 
66  case BT::NodeStatus::SUCCESS:
67  start_ = std::chrono::high_resolution_clock::now(); // Reset the timer
68  return BT::NodeStatus::SUCCESS;
69 
70  case BT::NodeStatus::FAILURE:
71  default:
72  return BT::NodeStatus::FAILURE;
73  }
74  }
75 
76  return status();
77 }
78 
79 } // namespace nav2_behavior_tree
80 
81 #include "behaviortree_cpp_v3/bt_factory.h"
82 BT_REGISTER_NODES(factory)
83 {
84  factory.registerNodeType<nav2_behavior_tree::RateController>("RateController");
85 }
A BT::DecoratorNode that ticks its child at a specified rate.
RateController(const std::string &name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::RateController.