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 
18 DelayNode::DelayNode(const std::string& name, const NodeConfiguration& config) :
19  DecoratorNode(name, config),
20  delay_started_(false),
21  delay_aborted_(false),
22  msec_(0),
24 {}
25 
27 {
29  {
30  if (!getInput("delay_msec", msec_))
31  {
32  throw RuntimeError("Missing parameter [delay_msec] in DelayNode");
33  }
34  }
35 
36  if (!delay_started_)
37  {
38  delay_complete_ = false;
39  delay_aborted_ = false;
40  delay_started_ = true;
42 
43  timer_id_ = timer_.add(std::chrono::milliseconds(msec_), [this](bool aborted) {
44  std::unique_lock<std::mutex> lk(delay_mutex_);
45  delay_complete_ = (!aborted);
46  if(!aborted)
47  {
49  }
50  });
51  }
52 
53  std::unique_lock<std::mutex> lk(delay_mutex_);
54 
55  if (delay_aborted_)
56  {
57  delay_aborted_ = false;
58  delay_started_ = false;
59  return NodeStatus::FAILURE;
60  }
61  else if (delay_complete_)
62  {
63  auto child_status = child()->executeTick();
64  if(child_status != NodeStatus::RUNNING)
65  {
66  delay_started_ = false;
67  delay_aborted_ = false;
68  resetChild();
69  }
70  return child_status;
71  }
72  else
73  {
74  return NodeStatus::RUNNING;
75  }
76 }
77 
78 } // namespace BT
bool read_parameter_from_ports_
Definition: delay_node.h:55
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:26
const NodeConfiguration & config() const
Definition: tree_node.cpp:127
TimerQueue timer_
Definition: delay_node.h:46
bool delay_complete_
Definition: delay_node.h:52
bool delay_aborted_
Definition: delay_node.h:53
const std::string & name() const
Name of the instance, not the type.
Definition: tree_node.cpp:101
bool delay_started_
Definition: delay_node.h:51
unsigned msec_
Definition: delay_node.h:54
Result getInput(const std::string &key, T &destination) const
Definition: tree_node.h:232
std::mutex delay_mutex_
Definition: delay_node.h:56
const TreeNode * child() const
void setRegistrationID(StringView ID)
Definition: tree_node.cpp:201
uint64_t add(std::chrono::milliseconds milliseconds, std::function< void(bool)> handler)
Adds a new timer.
Definition: timer_queue.h:86
void emitStateChanged()
Definition: tree_node.cpp:193
NodeStatus
Definition: basic_types.h:35
uint64_t timer_id_
Definition: delay_node.h:47
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
Definition: tree_node.cpp:32
void setStatus(NodeStatus new_status)
Definition: tree_node.cpp:63


behaviortree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Mon Jul 3 2023 02:50:14