Go to the documentation of this file.
59 throw LogicError(
"SyncActionNode MUST never return RUNNING");
65 #ifndef BT_NO_COROUTINES
67 #ifdef BT_BOOST_COROUTINE2
68 #include <boost/coroutine2/all.hpp>
69 using namespace boost::coroutines2;
72 #ifdef BT_BOOST_COROUTINE
73 #include <boost/coroutine/all.hpp>
74 using namespace boost::coroutines;
79 std::unique_ptr<coroutine<void>::pull_type>
coro;
80 std::function<void(coroutine<void>::push_type& yield)>
func;
87 _p->func = [
this](coroutine<void>::push_type& yield) {
88 _p->yield_ptr = &yield;
104 if (!(
_p->coro) || !(*
_p->coro))
106 _p->coro.reset(
new coroutine<void>::pull_type(
_p->func));
133 throw std::logic_error(
"StatefulActionNode::onStart() must not return IDLE");
143 throw std::logic_error(
"StatefulActionNode::onRunning() must not return "
149 return initial_status;
162 using lock_type = std::unique_lock<std::mutex>;
168 halt_requested_ =
false;
169 thread_handle_ = std::async(std::launch::async, [
this]() {
172 auto status = tick();
173 if (!isHaltRequested())
178 catch (std::exception&)
180 std::cerr <<
"\nUncaught exception from the method tick(): ["
181 << registrationName() <<
"/" << name() <<
"]\n"
185 exptr_ = std::current_exception();
197 const auto exptr_copy = exptr_;
199 std::rethrow_exception(exptr_copy);
SyncActionNode(const std::string &name, const NodeConfiguration &config)
virtual NodeStatus executeTick() override final
The method that should be used to invoke tick() and setStatus();.
std::atomic_bool halt_requested_
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
virtual void onHalted()=0
CoroActionNode(const std::string &name, const NodeConfiguration &config)
std::future< void > thread_handle_
std::function< NodeStatus(TreeNode &)> TickFunctor
virtual NodeStatus executeTick() override
throws if the derived class return RUNNING.
coroutine< void >::push_type * yield_ptr
NodeStatus status() const
void setStatus(NodeStatus new_status)
ActionNodeBase(const std::string &name, const NodeConfiguration &config)
TickFunctor tick_functor_
SimpleActionNode(const std::string &name, TickFunctor tick_functor, const NodeConfiguration &config)
virtual NodeStatus tick() override final
Method to be implemented by the user.
std::function< void(coroutine< void >::push_type &yield)> func
std::unique_ptr< coroutine< void >::pull_type > coro
virtual BT::NodeStatus tick()=0
Method to be implemented by the user.
virtual ~CoroActionNode() override
The ActionNodeBase is the base class to use to create any kind of action. A particular derived class ...
NodeStatus tick() override final
Method to be implemented by the user.
virtual NodeStatus onStart()=0
void setStatusRunningAndYield()
Use this method to return RUNNING and temporary "pause" the Action.
std::unique_ptr< Pimpl > _p
virtual NodeStatus executeTick() override final
The method that should be used to invoke tick() and setStatus();.
The SyncActionNode is an ActionNode that explicitly prevents the status RUNNING and doesn't require a...
virtual void halt() override
void halt() override final
virtual NodeStatus onRunning()=0
method invoked by a RUNNING action.
behaviortree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Wed Jun 26 2024 02:51:19