Skip to content

Commit 291db65

Browse files
committed
more docs
1 parent 6dcd5ff commit 291db65

File tree

2 files changed

+150
-59
lines changed

2 files changed

+150
-59
lines changed

docs/asynchronous_nodes.md

Lines changed: 135 additions & 58 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,11 @@ When designing reactive Behavior Trees, it is important to understand 2 main con
99

1010
If you Google those words, you will read many good articles about this topic.
1111

12+
!!! info "Defintions"
13+
**Concurrency** is when two or more tasks can start, run, and complete in overlapping time periods. It doesn't necessarily mean they'll ever both be running at the same instant.
14+
15+
**Parallelism** is when tasks literally run at the same time in different threads, e.g., on a multicore processor.
16+
1217
BT.CPP executes all the nodes **Concurrently**, in other words:
1318

1419
- The Tree execution engine itself is single-threaded.
@@ -51,43 +56,42 @@ class SleepNode : public BT::StatefulActionNode
5156

5257
static BT::PortsList providedPorts()
5358
{
54-
// amount of milliseconds that we want to sleep
55-
return{ BT::InputPort<int>("msec") };
59+
// amount of milliseconds that we want to sleep
60+
return{ BT::InputPort<int>("msec") };
5661
}
5762

5863
NodeStatus onStart() override
5964
{
60-
int msec = 0;
61-
getInput("msec", msec);
62-
if( msec <= 0 )
63-
{
64-
// No need to go into the RUNNING state
65-
return NodeStatus::SUCCESS;
66-
}
67-
else {
68-
using namespace std::chrono;
69-
// once the deadline is reached, we will return SUCCESS.
70-
deadline_ = system_clock::now() + milliseconds(msec);
71-
return NodeStatus::RUNNING;
72-
}
65+
int msec = 0;
66+
getInput("msec", msec);
67+
68+
if( msec <= 0 ) {
69+
// No need to go into the RUNNING state
70+
return NodeStatus::SUCCESS;
71+
}
72+
else {
73+
using namespace std::chrono;
74+
// once the deadline is reached, we will return SUCCESS.
75+
deadline_ = system_clock::now() + milliseconds(msec);
76+
return NodeStatus::RUNNING;
77+
}
7378
}
7479

7580
/// method invoked by an action in the RUNNING state.
7681
NodeStatus onRunning() override
7782
{
78-
if ( std::chrono::system_clock::now() >= deadline_ )
79-
{
80-
return NodeStatus::SUCCESS;
81-
}
82-
else {
83-
return NodeStatus::RUNNING;
84-
}
83+
if ( std::chrono::system_clock::now() >= deadline_ ) {
84+
return NodeStatus::SUCCESS;
85+
}
86+
else {
87+
return NodeStatus::RUNNING;
88+
}
8589
}
8690

8791
void onHalted() override
8892
{
89-
// nothing to do here...
90-
std::cout << "SleepNode interrupted" << std::endl;
93+
// nothing to do here...
94+
std::cout << "SleepNode interrupted" << std::endl;
9195
}
9296

9397
private:
@@ -118,23 +122,23 @@ class BadSleepNode : public BT::ActionNodeBase
118122
119123
static BT::PortsList providedPorts()
120124
{
121-
return{ BT::InputPort<int>("msec") };
125+
return{ BT::InputPort<int>("msec") };
122126
}
123127
124128
NodeStatus tick() override
125129
{
126-
int msec = 0;
127-
getInput("msec", msec);
128-
// This blocking function will FREEZE the entire tree :(
129-
std::this_thread::sleep_for( std::chrono::milliseconds(msec) );
130-
return NodeStatus::SUCCESS;
130+
int msec = 0;
131+
getInput("msec", msec);
132+
// This blocking function will FREEZE the entire tree :(
133+
std::this_thread::sleep_for( std::chrono::milliseconds(msec) );
134+
return NodeStatus::SUCCESS;
131135
}
132136
133137
void halt() override
134138
{
135-
// No one can invoke this method, because I freezed the tree.
136-
// Even if this method COULD be executed, there is no way I can
137-
// interrupt std::this_thread::sleep_for()
139+
// No one can invoke this method, because I freezed the tree.
140+
// Even if this method COULD be executed, there is no way I can
141+
// interrupt std::this_thread::sleep_for()
138142
}
139143
};
140144
```
@@ -164,18 +168,18 @@ class BadSleepNode : public BT::AsyncActionNode
164168

165169
static BT::PortsList providedPorts()
166170
{
167-
return{ BT::InputPort<int>("msec") };
171+
return{ BT::InputPort<int>("msec") };
168172
}
169173

170174
NodeStatus tick() override
171175
{
172-
// This code runs in its own thread, therefore the Tree is still running.
173-
// This seems good but the thread still can't be aborted
174-
int msec = 0;
175-
getInput("msec", msec);
176-
std::this_thread::sleep_for( std::chrono::milliseconds(msec) );
177-
return NodeStatus::SUCCESS;
178-
}
176+
// This code runs in its own thread, therefore the Tree is still running.
177+
// This seems good but the thread still can't be aborted
178+
int msec = 0;
179+
getInput("msec", msec);
180+
std::this_thread::sleep_for( std::chrono::milliseconds(msec) );
181+
return NodeStatus::SUCCESS;
182+
}
179183

180184
// The halt() method can not kill the spawned thread :(
181185

@@ -197,33 +201,106 @@ class ThreadedSleepNode : public BT::AsyncActionNode
197201
198202
static BT::PortsList providedPorts()
199203
{
200-
return{ BT::InputPort<int>("msec") };
204+
return{ BT::InputPort<int>("msec") };
201205
}
202206
203207
NodeStatus tick() override
204208
{
205-
// This code run in its own thread, therefore the Tree is still running.
206-
int msec = 0;
207-
getInput("msec", msec);
208-
209-
using namespace std::chrono;
210-
const auto deadline = system_clock::now() + milliseconds(msec);
211-
212-
// periodically check isHaltRequested()
213-
// and sleep for a small amount of time only (1 millisecond)
214-
while( !isHaltRequested() && system_clock::now() < deadline )
215-
{
216-
std::this_thread::sleep_for( std::chrono::milliseconds(1) );
217-
}
218-
return NodeStatus::SUCCESS;
219-
}
209+
// This code run in its own thread, therefore the Tree is still running.
210+
int msec = 0;
211+
getInput("msec", msec);
212+
213+
using namespace std::chrono;
214+
const auto deadline = system_clock::now() + milliseconds(msec);
215+
216+
// periodically check isHaltRequested()
217+
// and sleep for a small amount of time only (1 millisecond)
218+
while( !isHaltRequested() && system_clock::now() < deadline )
219+
{
220+
std::this_thread::sleep_for( std::chrono::milliseconds(1) );
221+
}
222+
return NodeStatus::SUCCESS;
223+
}
220224
221225
// The halt() method can not kill the spawned thread :()
222226
// void halt();
223-
}
224227
};
225228
```
226229

227230
As you can see, this looks more complicated than the version we implemented
228231
first, using `BT::StatefulActionNode`.
229232
This pattern can still be useful in some case, but you must remember that introducing multi-threading make things more complicated and **should be avoided by default**.
233+
234+
## Advanced example: client / server communication
235+
236+
Frequently, people using BT.CPP execute the actual task in a different process.
237+
238+
A typical (and recommended) way to do this in ROS is using [ActionLib](http://wiki.ros.org/actionlib).
239+
240+
ActionLib provides exactly the kind of API that we need to implement correctly an asynchronous behavior:
241+
242+
1. A non-blocking function to start the Action.
243+
2. A way to monitor the current state of execution of the Action.
244+
3. A way to retrieve the result or the error messages.
245+
4. The avility to preempt / abort an action that is being executed.
246+
247+
None of these operations are "blocking", therefore we don't need to spawn our own thread.
248+
249+
More generally, let's assume that the developer has their own inter-processing communication, with a client/server relationship between the BT executor and the actual service provider.
250+
251+
The corresponding **pseudo-code** implementation will look like this:
252+
253+
```c++
254+
// This action talk to a remote server
255+
class ActionClientNode : public BT::StatefulActionNode
256+
{
257+
public:
258+
SleepNode(const std::string& name, const BT::NodeConfiguration& config)
259+
: BT::StatefulActionNode(name, config)
260+
{}
261+
262+
NodeStatus onStart() override
263+
{
264+
// send a request to the server
265+
bool accepted = sendStartRequestToServer();
266+
// check if the request was rejected
267+
if( !accepted ) {
268+
return NodeStatus::FAILURE;
269+
}
270+
else {
271+
return NodeStatus::RUNNING;
272+
}
273+
}
274+
275+
/// method invoked by an action in the RUNNING state.
276+
NodeStatus onRunning() override
277+
{
278+
// more psuedo-code
279+
auto request_state = getCurrentStateFromServer();
280+
281+
if( request_state == DONE )
282+
{
283+
auto result = getResult();
284+
if( IsValidResult(result) ) {
285+
return NodeStatus::SUCCESS;
286+
}
287+
else {
288+
return NodeStatus::FAILURE;
289+
}
290+
}
291+
else if( request_state == ABORTED ) {
292+
return NodeStatus::FAILURE;
293+
}
294+
else {
295+
// request_state == EXECUTING ?
296+
return NodeStatus::RUNNING;
297+
}
298+
}
299+
300+
void onHalted() override
301+
{
302+
// notify the server that the operation have been aborted
303+
sendAbortSignalToServer();
304+
}
305+
};
306+
```

docs/tutorial_07_multiple_xml.md

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,21 @@ If we don't want to add relative and hard-coded paths into our XML,
6262
or if we want to instantiate a subtree instead of the main tree, there is a
6363
new approach, since BT.CPP 3.7+.
6464

65-
This process requires few more steps, but offers more flexibility.
65+
The simplified version of **main_tree.xml** will be:
66+
67+
```XML
68+
<root>
69+
<BehaviorTree ID="MainTree">
70+
<Sequence>
71+
<SaySomething message="starting MainTree" />
72+
<SubTree ID="SubTreeA" />
73+
<SubTree ID="SubTreeB" />
74+
</Sequence>
75+
</BehaviorTree>
76+
<root>
77+
```
78+
79+
To load manually the multiple files:
6680

6781
```c++
6882
int main()

0 commit comments

Comments
 (0)