Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
time_expired_condition.cpp
1 // Copyright (c) 2019 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 
19 #include "behaviortree_cpp/condition_node.h"
20 
21 #include "nav2_behavior_tree/plugins/condition/time_expired_condition.hpp"
22 
23 namespace nav2_behavior_tree
24 {
25 
26 TimeExpiredCondition::TimeExpiredCondition(
27  const std::string & condition_name,
28  const BT::NodeConfiguration & conf)
29 : BT::ConditionNode(condition_name, conf),
30  period_(1.0)
31 {
32 }
33 
35 {
36  getInput("seconds", period_);
37  node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
38  start_ = node_->now();
39 }
40 
42 {
43  if (!BT::isStatusActive(status())) {
44  initialize();
45  }
46 
47  if (!BT::isStatusActive(status())) {
48  start_ = node_->now();
49  return BT::NodeStatus::FAILURE;
50  }
51 
52  // Determine how long its been since we've started this iteration
53  auto elapsed = node_->now() - start_;
54 
55  // Now, get that in seconds
56  auto seconds = elapsed.seconds();
57 
58  if (seconds < period_) {
59  return BT::NodeStatus::FAILURE;
60  }
61 
62  start_ = node_->now(); // Reset the timer
63  return BT::NodeStatus::SUCCESS;
64 }
65 
66 } // namespace nav2_behavior_tree
67 
68 #include "behaviortree_cpp/bt_factory.h"
69 BT_REGISTER_NODES(factory)
70 {
71  factory.registerNodeType<nav2_behavior_tree::TimeExpiredCondition>("TimeExpired");
72 }
A BT::ConditionNode that returns SUCCESS every time a specified time period passes and FAILURE otherw...
BT::NodeStatus tick() override
The main override required by a BT action.
void initialize()
Function to read parameters and initialize class variables.