@@ -101,6 +101,10 @@ class SimpleActionNode : public SyncActionNode
101
101
*
102
102
* The user must implement the methods tick() and halt().
103
103
*
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.
104
108
*/
105
109
class AsyncActionNode : public ActionNodeBase
106
110
{
@@ -136,6 +140,46 @@ class AsyncActionNode : public ActionNodeBase
136
140
std::thread thread_;
137
141
};
138
142
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
+
139
183
#ifndef BT_NO_COROUTINES
140
184
141
185
/* *
0 commit comments