delay_node.cpp
Go to the documentation of this file.
1 /* Contributed by Indraneel on 26/04/2020
2 */
5 
6 namespace BT
7 {
8 DelayNode::DelayNode(const std::string& name, unsigned milliseconds)
9  : DecoratorNode(name, {})
10  , delay_started_(false)
11  , delay_aborted_(false)
12  , msec_(milliseconds)
14 {
15  setRegistrationID("Delay");
16 }
17 
19  : DecoratorNode(name, config)
20  , delay_started_(false)
21  , delay_aborted_(false)
22  , msec_(0)
24 {
25 }
26 
28 {
30  {
31  if (!getInput("delay_msec", msec_))
32  {
33  throw RuntimeError("Missing parameter [delay_msec] in DelayNode");
34  }
35  }
36 
37  if (!delay_started_)
38  {
39  delay_complete_ = false;
40  delay_aborted_ = false;
41  delay_started_ = true;
43 
44  timer_id_ = timer_.add(std::chrono::milliseconds(msec_),
45  [this](bool aborted)
46  {
47  std::unique_lock<std::mutex> lk(delay_mutex_);
48  if (!aborted)
49  {
50  delay_complete_ = true;
51  }
52  else
53  {
54  delay_aborted_ = true;
55  }
56  });
57  }
58 
59  std::unique_lock<std::mutex> lk(delay_mutex_);
60 
61  if (delay_aborted_)
62  {
63  delay_aborted_ = false;
64  delay_started_ = false;
65  return NodeStatus::FAILURE;
66  }
67  else if (delay_complete_)
68  {
69  delay_started_ = false;
70  delay_aborted_ = false;
71  auto child_status = child()->executeTick();
72  return child_status;
73  }
74  else
75  {
76  return NodeStatus::RUNNING;
77  }
78 }
79 
80 } // namespace BT
bool read_parameter_from_ports_
Definition: delay_node.h:57
const TreeNode * child() const
const std::string & name() const
Name of the instance, not the type.
Definition: tree_node.cpp:73
DelayNode(const std::string &name, unsigned milliseconds)
Definition: delay_node.cpp:8
virtual BT::NodeStatus tick() override
Method to be implemented by the user.
Definition: delay_node.cpp:27
const NodeConfiguration & config() const
Definition: tree_node.cpp:99
TimerQueue timer_
Definition: delay_node.h:48
bool delay_complete_
Definition: delay_node.h:54
bool delay_aborted_
Definition: delay_node.h:55
bool delay_started_
Definition: delay_node.h:53
unsigned msec_
Definition: delay_node.h:56
Result getInput(const std::string &key, T &destination) const
Definition: tree_node.h:192
std::mutex delay_mutex_
Definition: delay_node.h:58
void setRegistrationID(StringView ID)
Definition: tree_node.h:163
uint64_t add(std::chrono::milliseconds milliseconds, std::function< void(bool)> handler)
Adds a new timer.
Definition: timer_queue.h:86
NodeStatus
Definition: basic_types.h:35
uint64_t timer_id_
Definition: delay_node.h:49
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
Definition: tree_node.cpp:33
void setStatus(NodeStatus new_status)
Definition: tree_node.cpp:40


behaviotree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Tue May 4 2021 02:56:24