action_node.cpp
Go to the documentation of this file.
1 /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved
2  * Copyright (C) 2018-2023 Davide Faconti - All Rights Reserved
3 *
4 * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
5 * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
6 * and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
7 * The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
8 *
9 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
10 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
11 * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
12 */
13 
14 #define MINICORO_IMPL
15 #include "minicoro/minicoro.h"
17 
18 using namespace BT;
19 
20 ActionNodeBase::ActionNodeBase(const std::string& name, const NodeConfig& config)
21  : LeafNode::LeafNode(name, config)
22 {}
23 
24 //-------------------------------------------------------
25 
26 SimpleActionNode::SimpleActionNode(const std::string& name,
27  SimpleActionNode::TickFunctor tick_functor,
28  const NodeConfig& config)
29  : SyncActionNode(name, config), tick_functor_(std::move(tick_functor))
30 {}
31 
33 {
34  NodeStatus prev_status = status();
35 
36  if(prev_status == NodeStatus::IDLE)
37  {
39  prev_status = NodeStatus::RUNNING;
40  }
41 
43  if(status != prev_status)
44  {
46  }
47  return status;
48 }
49 
50 //-------------------------------------------------------
51 
52 SyncActionNode::SyncActionNode(const std::string& name, const NodeConfig& config)
53  : ActionNodeBase(name, config)
54 {}
55 
57 {
58  auto stat = ActionNodeBase::executeTick();
59  if(stat == NodeStatus::RUNNING)
60  {
61  throw LogicError("SyncActionNode MUST never return RUNNING");
62  }
63  return stat;
64 }
65 
66 //-------------------------------------
67 
69 {
70  mco_coro* coro = nullptr;
72 };
73 
75 {
76  static_cast<CoroActionNode*>(co->user_data)->tickImpl();
77 }
78 
79 CoroActionNode::CoroActionNode(const std::string& name, const NodeConfig& config)
80  : ActionNodeBase(name, config), _p(new Pimpl)
81 {}
82 
84 {
86 }
87 
89 {
91  mco_yield(_p->coro);
92 }
93 
95 {
96  // create a new coroutine, if necessary
97  if(_p->coro == nullptr)
98  {
99  // First initialize a `desc` object through `mco_desc_init`.
100  _p->desc = mco_desc_init(CoroEntry, 0);
101  _p->desc.user_data = this;
102 
103  mco_result res = mco_create(&_p->coro, &_p->desc);
104  if(res != MCO_SUCCESS)
105  {
106  throw RuntimeError("Can't create coroutine");
107  }
108  }
109 
110  //------------------------
111  // execute the coroutine
112  mco_resume(_p->coro);
113  //------------------------
114 
115  // check if the coroutine finished. In this case, destroy it
116  if(mco_status(_p->coro) == MCO_DEAD)
117  {
119  }
120 
121  return status();
122 }
123 
125 {
127 }
128 
130 {
132  resetStatus(); // might be redundant
133 }
134 
136 {
137  if(_p->coro)
138  {
139  mco_result res = mco_destroy(_p->coro);
140  if(res != MCO_SUCCESS)
141  {
142  throw RuntimeError("Can't destroy coroutine");
143  }
144  _p->coro = nullptr;
145  }
146 }
147 
149 {
150  return halt_requested_.load();
151 }
152 
154 {
155  const NodeStatus prev_status = status();
156 
157  if(prev_status == NodeStatus::IDLE)
158  {
159  NodeStatus new_status = onStart();
160  if(new_status == NodeStatus::IDLE)
161  {
162  throw LogicError("StatefulActionNode::onStart() must not return IDLE");
163  }
164  return new_status;
165  }
166  //------------------------------------------
167  if(prev_status == NodeStatus::RUNNING)
168  {
169  NodeStatus new_status = onRunning();
170  if(new_status == NodeStatus::IDLE)
171  {
172  throw LogicError("StatefulActionNode::onRunning() must not return IDLE");
173  }
174  return new_status;
175  }
176  return prev_status;
177 }
178 
180 {
181  halt_requested_.store(true);
182  if(status() == NodeStatus::RUNNING)
183  {
184  onHalted();
185  }
186  resetStatus(); // might be redundant
187 }
188 
190 {
191  using lock_type = std::unique_lock<std::mutex>;
192  //send signal to other thread.
193  // The other thread is in charge for changing the status
194  if(status() == NodeStatus::IDLE)
195  {
196  setStatus(NodeStatus::RUNNING);
197  halt_requested_ = false;
198  thread_handle_ = std::async(std::launch::async, [this]() {
199  try
200  {
201  auto status = tick();
202  if(!isHaltRequested())
203  {
204  setStatus(status);
205  }
206  }
207  catch(std::exception&)
208  {
209  std::cerr << "\nUncaught exception from tick(): [" << registrationName() << "/"
210  << name() << "]\n"
211  << std::endl;
212  // Set the exception pointer and the status atomically.
213  lock_type l(mutex_);
214  exptr_ = std::current_exception();
215  setStatus(BT::NodeStatus::IDLE);
216  }
217  emitWakeUpSignal();
218  });
219  }
220 
221  lock_type l(mutex_);
222  if(exptr_)
223  {
224  // The official interface of std::exception_ptr does not define any move
225  // semantics. Thus, we copy and reset exptr_ manually.
226  const auto exptr_copy = exptr_;
227  exptr_ = nullptr;
228  std::rethrow_exception(exptr_copy);
229  }
230  return status();
231 }
232 
234 {
235  halt_requested_.store(true);
236 
237  if(thread_handle_.valid())
238  {
239  thread_handle_.wait();
240  }
241  thread_handle_ = {};
242  resetStatus(); // might be redundant
243 }
BT
Definition: ex01_wrap_legacy.cpp:29
mco_yield
MCO_API mco_result mco_yield(mco_coro *co)
BT::StatefulActionNode::isHaltRequested
bool isHaltRequested() const
Definition: action_node.cpp:148
mco_desc
Definition: minicoro.h:266
BT::CoroActionNode::Pimpl
Definition: action_node.cpp:68
BT::CoroActionNode::executeTick
virtual NodeStatus executeTick() override final
The method that should be used to invoke tick() and setStatus();.
Definition: action_node.cpp:94
BT::LeafNode
Definition: leaf_node.h:21
mco_result
mco_result
Definition: minicoro.h:228
mco_coro::user_data
void * user_data
Definition: minicoro.h:251
mco_status
MCO_API mco_state mco_status(mco_coro *co)
BT::TreeNode::executeTick
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
Definition: tree_node.cpp:71
CoroEntry
void CoroEntry(mco_coro *co)
Definition: action_node.cpp:74
mco_create
MCO_API mco_result mco_create(mco_coro **out_co, mco_desc *desc)
mco_resume
MCO_API mco_result mco_resume(mco_coro *co)
BT::CoroActionNode::tickImpl
void tickImpl()
Definition: action_node.cpp:124
MCO_SUCCESS
@ MCO_SUCCESS
Definition: minicoro.h:229
BT::StatefulActionNode::onHalted
virtual void onHalted()=0
mco_coro
Definition: minicoro.h:246
BT::LogicError
Definition: exceptions.h:45
BT::ActionNodeBase::ActionNodeBase
ActionNodeBase(const std::string &name, const NodeConfig &config)
Definition: action_node.cpp:20
BT::CoroActionNode::halt
void halt() override
Definition: action_node.cpp:129
MCO_DEAD
@ MCO_DEAD
Definition: minicoro.h:221
BT::SyncActionNode::executeTick
virtual NodeStatus executeTick() override
throws if the derived class return RUNNING.
Definition: action_node.cpp:56
BT::ThreadedAction::halt_requested_
std::atomic_bool halt_requested_
Definition: action_node.h:135
BT::CoroActionNode::Pimpl::desc
mco_desc desc
Definition: action_node.cpp:71
BT::CoroActionNode::destroyCoroutine
void destroyCoroutine()
Definition: action_node.cpp:135
mco_desc_init
MCO_API mco_desc mco_desc_init(void(*func)(mco_coro *co), size_t stack_size)
BT::TreeNode::status
NodeStatus status() const
Definition: tree_node.cpp:279
BT::CoroActionNode::CoroActionNode
CoroActionNode(const std::string &name, const NodeConfig &config)
Definition: action_node.cpp:79
BT::TreeNode::setStatus
void setStatus(NodeStatus new_status)
setStatus changes the status of the node. it will throw if you try to change the status to IDLE,...
Definition: tree_node.cpp:154
action_node.h
BT::ThreadedAction::thread_handle_
std::future< void > thread_handle_
Definition: action_node.h:136
BT::SyncActionNode::SyncActionNode
SyncActionNode(const std::string &name, const NodeConfig &config)
Definition: action_node.cpp:52
BT::SimpleActionNode::tick_functor_
TickFunctor tick_functor_
Definition: action_node.h:93
BT::SimpleActionNode::tick
virtual NodeStatus tick() override final
Method to be implemented by the user.
Definition: action_node.cpp:32
BT::RuntimeError
Definition: exceptions.h:58
BT::SimpleActionNode::SimpleActionNode
SimpleActionNode(const std::string &name, TickFunctor tick_functor, const NodeConfig &config)
Definition: action_node.cpp:26
BT::CoroActionNode::~CoroActionNode
virtual ~CoroActionNode() override
Definition: action_node.cpp:83
BT::ActionNodeBase
The ActionNodeBase is the base class to use to create any kind of action. A particular derived class ...
Definition: action_node.h:35
BT::NodeStatus::RUNNING
@ RUNNING
BT::StatefulActionNode::tick
NodeStatus tick() override final
Method to be implemented by the user.
Definition: action_node.cpp:153
BT::StatefulActionNode::onStart
virtual NodeStatus onStart()=0
BT::CoroActionNode::Pimpl::coro
mco_coro * coro
Definition: action_node.cpp:70
BT::CoroActionNode::setStatusRunningAndYield
void setStatusRunningAndYield()
Use this method to return RUNNING and temporary "pause" the Action.
Definition: action_node.cpp:88
BT::ThreadedAction::halt
virtual void halt() override
Definition: action_node.cpp:233
BT::CoroActionNode::_p
std::unique_ptr< Pimpl > _p
Definition: action_node.h:225
BT::TreeNode::resetStatus
void resetStatus()
Set the status to IDLE.
Definition: tree_node.cpp:262
std
Definition: std.hpp:30
mco_destroy
MCO_API mco_result mco_destroy(mco_coro *co)
BT::NodeStatus::IDLE
@ IDLE
BT::StatefulActionNode::halt_requested_
std::atomic_bool halt_requested_
Definition: action_node.h:186
BT::ThreadedAction::executeTick
virtual NodeStatus executeTick() override final
The method that should be used to invoke tick() and setStatus();.
Definition: action_node.cpp:189
BT::NodeConfig
Definition: tree_node.h:73
BT::SyncActionNode
The SyncActionNode is an ActionNode that explicitly prevents the status RUNNING and doesn't require a...
Definition: action_node.h:52
minicoro.h
BT::SimpleActionNode::TickFunctor
std::function< NodeStatus(TreeNode &)> TickFunctor
Definition: action_node.h:82
BT::NodeStatus
NodeStatus
Definition: basic_types.h:33
BT::StatefulActionNode::halt
void halt() override final
Definition: action_node.cpp:179
BT::StatefulActionNode::onRunning
virtual NodeStatus onRunning()=0
method invoked when the action is already in the RUNNING state.
BT::CoroActionNode
The CoroActionNode class is an a good candidate for asynchronous actions which need to communicate wi...
Definition: action_node.h:196


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Fri Jun 28 2024 02:20:07