|
| 1 | +# Understand Asynchrous Nodes, Concurrency and Parallelism |
| 2 | + |
| 3 | +When designing reactive Behavior Trees, it is important to understand 2 main concepts: |
| 4 | + |
| 5 | +- what we mean by **"Asynchronous"** Actions VS **"Synchronous"** ones. |
| 6 | +- The difference between **Concurrency** and **Parallelism** in general and in the context of BT.CPP. |
| 7 | + |
| 8 | +## Concurrency vs Parallelism |
| 9 | + |
| 10 | +If you Google those words, you will read many good articles about this topic. |
| 11 | + |
| 12 | +BT.CPP executes all the nodes **Concurrently**, in other words: |
| 13 | + |
| 14 | +- The Tree execution engine itself is single-threaded. |
| 15 | +- all the `tick()` methods are **always** executed sequentially. |
| 16 | +- if any `tick()` method is blocking, the entire execution is blocked. |
| 17 | + |
| 18 | +We achieve reactive behaviors through "concurrency" and asynchronous execution. |
| 19 | + |
| 20 | +In other words, an Action that takes a long time to execute should, instead, |
| 21 | +return as soon as possible the state RUNNING to notify that the action was started, |
| 22 | +and only when ticked again check if the action is completed or not. |
| 23 | + |
| 24 | +An Asynchronous node may delegate this long execution either to another process, |
| 25 | +another server or simply another thread. |
| 26 | + |
| 27 | +## Asynchronous vs Synchronous |
| 28 | + |
| 29 | +In general, an Asynchronous Action (or TreeNode) is simply one that: |
| 30 | + |
| 31 | +- May return RUNNING instead of SUCCESS or FAILURE, when ticked. |
| 32 | +- Can be stopped as fast as possible when the method `halt()` (to be implemented by the developer) is invoked. |
| 33 | + |
| 34 | +When your Tree ends up executing an Asynchronous action that returns running, that RUNNING state is usually propagated backbard and the entire Tree is itself in the RUNNING state. |
| 35 | + |
| 36 | +In the example below, "ActionE" is asynchronous and the RUNNING; when |
| 37 | +a node is RUNNING, usually its parent returns RUNNING too. |
| 38 | + |
| 39 | + |
| 40 | + |
| 41 | +Let's consider a simple "SleepNode". A good template to get started is the StatefullAction |
| 42 | + |
| 43 | +```c++ |
| 44 | +// Example os Asynchronous node that use StatefulActionNode as base class |
| 45 | +class SleepNode : public BT::StatefulActionNode |
| 46 | +{ |
| 47 | + public: |
| 48 | + SleepNode(const std::string& name, const BT::NodeConfiguration& config) |
| 49 | + : BT::StatefulActionNode(name, config) |
| 50 | + {} |
| 51 | + |
| 52 | + static BT::PortsList providedPorts() |
| 53 | + { |
| 54 | + // amount of milliseconds that we want to sleep |
| 55 | + return{ BT::InputPort<int>("msec") }; |
| 56 | + } |
| 57 | + |
| 58 | + NodeStatus onStart() override |
| 59 | + { |
| 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 | + } |
| 73 | + } |
| 74 | + |
| 75 | + /// method invoked by an action in the RUNNING state. |
| 76 | + NodeStatus onRunning() override |
| 77 | + { |
| 78 | + if ( std::chrono::system_clock::now() >= deadline_ ) |
| 79 | + { |
| 80 | + return NodeStatus::SUCCESS; |
| 81 | + } |
| 82 | + else { |
| 83 | + return NodeStatus::RUNNING; |
| 84 | + } |
| 85 | + } |
| 86 | + |
| 87 | + void onHalted() override |
| 88 | + { |
| 89 | + // nothing to do here... |
| 90 | + std::cout << "SleepNode interrupted" << std::endl; |
| 91 | + } |
| 92 | + |
| 93 | + private: |
| 94 | + std::chrono::system_clock::time_point deadline_; |
| 95 | +}; |
| 96 | +``` |
| 97 | +
|
| 98 | +In the code above: |
| 99 | +
|
| 100 | +1. When the SleedNode is ticked the first time, the `onStart()` method is executed. |
| 101 | +This may return SUCCESS immediately if the sleep time is 0 or will return RUNNING otherwise. |
| 102 | +2. We should continue ticking the tree in a loop. This will invoke the method |
| 103 | +`onRunning()` that may return RUNNING again or, eventually, SUCCESS. |
| 104 | +3. Another node might trigger a `halt()` signal. In this case, the `onHalted()` method is invoked. We can take the opportunity to clean up our internal state. |
| 105 | +
|
| 106 | +## Avoid blocking the execution of the tree |
| 107 | +
|
| 108 | +A **wrong** way to implement the `SleepNode` would be this one: |
| 109 | +
|
| 110 | +```c++ |
| 111 | +// This is the synchronous version of the Node. probably not what we want. |
| 112 | +class BadSleepNode : public BT::ActionNodeBase |
| 113 | +{ |
| 114 | + public: |
| 115 | + BadSleepNode(const std::string& name, const BT::NodeConfiguration& config) |
| 116 | + : BT::ActionNodeBase(name, config) |
| 117 | + {} |
| 118 | +
|
| 119 | + static BT::PortsList providedPorts() |
| 120 | + { |
| 121 | + return{ BT::InputPort<int>("msec") }; |
| 122 | + } |
| 123 | +
|
| 124 | + NodeStatus tick() override |
| 125 | + { |
| 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; |
| 131 | + } |
| 132 | +
|
| 133 | + void halt() override |
| 134 | + { |
| 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() |
| 138 | + } |
| 139 | +}; |
| 140 | +``` |
| 141 | + |
| 142 | +## The problem with multi-threading |
| 143 | + |
| 144 | +In the early days of this library (version 1.x), spawning a new thread |
| 145 | +looked as a good solution to build asynchronous Actions. |
| 146 | + |
| 147 | +That was a bad idea, for multiple reasons: |
| 148 | + |
| 149 | +- Accessing the blackboard in a thread-safe way is harder (more about this later). |
| 150 | +- You probably don't need to. |
| 151 | +- People think that this will magically make the Action "asynchronous", but they forget that it is still **their responsibility** to stop that thread "somehow" when the `halt()`method is invoked. |
| 152 | + |
| 153 | +For this reason, user a usually discouraged from using `BT::AsyncActionNode` as a |
| 154 | +base class. Let's have a look again at the SleepNode. |
| 155 | + |
| 156 | +```c++ |
| 157 | +// This will spawn its own thread. But it still have problems when halted |
| 158 | +class BadSleepNode : public BT::AsyncActionNode |
| 159 | +{ |
| 160 | + public: |
| 161 | + BadSleepNode(const std::string& name, const BT::NodeConfiguration& config) |
| 162 | + : BT::ActionNodeBase(name, config) |
| 163 | + {} |
| 164 | + |
| 165 | + static BT::PortsList providedPorts() |
| 166 | + { |
| 167 | + return{ BT::InputPort<int>("msec") }; |
| 168 | + } |
| 169 | + |
| 170 | + NodeStatus tick() override |
| 171 | + { |
| 172 | + // This code run in its own thread, therefore the Tree is still running. |
| 173 | + // Think looks good but the thread 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 | + } |
| 179 | + |
| 180 | + // The halt() method can not kill the spawned thread :() |
| 181 | + // void halt(); |
| 182 | + } |
| 183 | +}; |
| 184 | +``` |
| 185 | +
|
| 186 | +A "correct" (but over-engineered) version of it would be: |
| 187 | +
|
| 188 | +```c++ |
| 189 | +// I will create my own thread here, for no good reason |
| 190 | +class ThreadedSleepNode : public BT::AsyncActionNode |
| 191 | +{ |
| 192 | + public: |
| 193 | + ThreadedSleepNode(const std::string& name, const BT::NodeConfiguration& config) |
| 194 | + : BT::ActionNodeBase(name, config) |
| 195 | + {} |
| 196 | +
|
| 197 | + static BT::PortsList providedPorts() |
| 198 | + { |
| 199 | + return{ BT::InputPort<int>("msec") }; |
| 200 | + } |
| 201 | +
|
| 202 | + NodeStatus tick() override |
| 203 | + { |
| 204 | + // This code run in its own thread, therefore the Tree is still running. |
| 205 | + int msec = 0; |
| 206 | + getInput("msec", msec); |
| 207 | +
|
| 208 | + using namespace std::chrono; |
| 209 | + auto deadline = system_clock::now() + milliseconds(msec); |
| 210 | +
|
| 211 | + // periodically check isHaltRequested() |
| 212 | + // and sleep for a small amount of time only (1 millisecond) |
| 213 | + while( !isHaltRequested() && system_clock::now() < deadline ) |
| 214 | + { |
| 215 | + std::this_thread::sleep_for( std::chrono::milliseconds(1) ); |
| 216 | + } |
| 217 | + return NodeStatus::SUCCESS; |
| 218 | + } |
| 219 | +
|
| 220 | + // The halt() method can not kill the spawned thread :() |
| 221 | + // void halt(); |
| 222 | + } |
| 223 | +}; |
| 224 | +``` |
| 225 | + |
| 226 | +As you can see, this looks more complicated than the version we implemented |
| 227 | +first, using `BT::StatefulActionNode`. |
| 228 | +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**. |
0 commit comments