Thanks to visit codestin.com
Credit goes to github.com

Skip to content

Commit d68afa6

Browse files
committed
adding StatefulActionNode
1 parent d597a6a commit d68afa6

File tree

2 files changed

+80
-0
lines changed

2 files changed

+80
-0
lines changed

include/behaviortree_cpp_v3/action_node.h

Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -101,6 +101,10 @@ class SimpleActionNode : public SyncActionNode
101101
*
102102
* The user must implement the methods tick() and halt().
103103
*
104+
* WARNING: this should probably be deprecated. It is too easy to use incorrectly
105+
* and there is not a good way to halt it in a thread safe way.
106+
*
107+
* Use it at your own risk.
104108
*/
105109
class AsyncActionNode : public ActionNodeBase
106110
{
@@ -136,6 +140,46 @@ class AsyncActionNode : public ActionNodeBase
136140
std::thread thread_;
137141
};
138142

143+
/**
144+
* @brief The ActionNode is the goto option for,
145+
* but it is actually much easier to use correctly.
146+
*
147+
* It is particularly useful when your code contains a request-reply pattern,
148+
* i.e. when the actions sends an asychronous request, then checks periodically
149+
* if the reply has been received and, eventually, analyze the reply to determine
150+
* if the result is SUCCESS or FAILURE.
151+
*
152+
* -) an IDLE action will call onStart()
153+
*
154+
* -) A RUNNING action will call onRunning()
155+
*
156+
* -) if halted, method onHalted()
157+
*/
158+
class StatefulActionNode : public ActionNodeBase
159+
{
160+
public:
161+
StatefulActionNode(const std::string& name, const NodeConfiguration& config):
162+
ActionNodeBase(name,config)
163+
{}
164+
165+
// do not override this method
166+
NodeStatus tick() override final;
167+
// do not override this method
168+
void halt() override final;
169+
170+
/// method to be called at the beginning.
171+
/// If it returns RUNNING, this becomes an asychronous node.
172+
virtual NodeStatus onStart() = 0;
173+
174+
/// method invoked by a RUNNING action.
175+
virtual NodeStatus onRunning() = 0;
176+
177+
/// when the method halt() is called by a parent node, this method
178+
/// is invoked to do the cleanup of a RUNNING action.
179+
virtual void onHalted() = 0;
180+
};
181+
182+
139183
#ifndef BT_NO_COROUTINES
140184

141185
/**

src/action_node.cpp

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -233,3 +233,39 @@ void CoroActionNode::halt()
233233
#endif
234234

235235

236+
237+
NodeStatus StatefulActionNode::tick()
238+
{
239+
const NodeStatus initial_status = status();
240+
241+
if( initial_status == NodeStatus::IDLE )
242+
{
243+
NodeStatus new_status = onStart();
244+
if( new_status == NodeStatus::IDLE)
245+
{
246+
throw std::logic_error("AsyncActionNode2::onStart() must not return IDLE");
247+
}
248+
return new_status;
249+
}
250+
//------------------------------------------
251+
if( initial_status == NodeStatus::RUNNING )
252+
{
253+
NodeStatus new_status = onRunning();
254+
if( new_status == NodeStatus::IDLE)
255+
{
256+
throw std::logic_error("AsyncActionNode2::onRunning() must not return IDLE");
257+
}
258+
return new_status;
259+
}
260+
//------------------------------------------
261+
return initial_status;
262+
}
263+
264+
void StatefulActionNode::halt()
265+
{
266+
if( status() == NodeStatus::RUNNING)
267+
{
268+
onHalted();
269+
}
270+
setStatus(NodeStatus::IDLE);
271+
}

0 commit comments

Comments
 (0)