@@ -32,8 +32,6 @@ struct TreeExecutionServer::Pimpl
3232{
3333 rclcpp_action::Server<ExecuteTree>::SharedPtr action_server;
3434 std::thread action_thread;
35- // thread safe bool to keep track of cancel requests
36- std::atomic<bool > cancel_requested{ false };
3735
3836 std::shared_ptr<bt_server::ParamListener> param_listener;
3937 bt_server::Params params;
@@ -43,7 +41,7 @@ struct TreeExecutionServer::Pimpl
4341
4442 std::string tree_name;
4543 std::string payload;
46- std::shared_ptr< BT::Tree> tree;
44+ BT::Tree tree;
4745 BT::Blackboard::Ptr global_blackboard;
4846 bool factory_initialized_ = false ;
4947
@@ -123,7 +121,6 @@ TreeExecutionServer::handle_goal(const rclcpp_action::GoalUUID& /* uuid */,
123121{
124122 RCLCPP_INFO (kLogger , " Received goal request to execute Behavior Tree: %s" ,
125123 goal->target_tree .c_str ());
126- p_->cancel_requested = false ;
127124 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
128125}
129126
@@ -137,7 +134,6 @@ rclcpp_action::CancelResponse TreeExecutionServer::handle_cancel(
137134 " processing one." );
138135 return rclcpp_action::CancelResponse::REJECT;
139136 }
140- p_->cancel_requested = true ;
141137 return rclcpp_action::CancelResponse::ACCEPT;
142138}
143139
@@ -172,30 +168,29 @@ void TreeExecutionServer::execute(
172168 // This blackboard will be owned by "MainTree". It parent is p_->global_blackboard
173169 auto root_blackboard = BT::Blackboard::create (p_->global_blackboard );
174170
175- p_->tree = std::make_shared<BT::Tree>();
176- *(p_->tree ) = p_->factory .createTree (goal->target_tree , root_blackboard);
171+ p_->tree = p_->factory .createTree (goal->target_tree , root_blackboard);
177172 p_->tree_name = goal->target_tree ;
178173 p_->payload = goal->payload ;
179174
180175 // call user defined function after the tree has been created
181- onTreeCreated (* p_->tree );
176+ onTreeCreated (p_->tree );
182177 p_->groot_publisher .reset ();
183178 p_->groot_publisher =
184- std::make_shared<BT::Groot2Publisher>(*( p_->tree ) , p_->params .groot2_port );
179+ std::make_shared<BT::Groot2Publisher>(p_->tree , p_->params .groot2_port );
185180
186181 // Loop until the tree is done or a cancel is requested
187182 const auto period =
188183 std::chrono::milliseconds (static_cast <int >(1000.0 / p_->params .tick_frequency ));
189184 auto loop_deadline = std::chrono::steady_clock::now () + period;
190185
191186 // operations to be done if the tree execution is aborted, either by
192- // cancel_requested_ or by onLoopAfterTick()
187+ // cancel requested or by onLoopAfterTick()
193188 auto stop_action = [this , &action_result](BT::NodeStatus status,
194189 const std::string& message) {
195190 action_result->node_status = ConvertNodeStatus (status);
196191 action_result->return_message = message;
197192 RCLCPP_WARN (kLogger , action_result->return_message .c_str ());
198- p_->tree -> haltTree ();
193+ p_->tree . haltTree ();
199194 // override the message value if the user defined function returns it
200195 if (auto msg = onTreeExecutionCompleted (status, true ))
201196 {
@@ -205,15 +200,15 @@ void TreeExecutionServer::execute(
205200
206201 while (rclcpp::ok () && status == BT::NodeStatus::RUNNING)
207202 {
208- if (p_-> cancel_requested )
203+ if (goal_handle-> is_canceling () )
209204 {
210205 stop_action (status, " Action Server canceling and halting Behavior Tree" );
211206 goal_handle->canceled (action_result);
212207 return ;
213208 }
214209
215210 // tick the tree once and publish the action feedback
216- status = p_->tree -> tickExactlyOnce ();
211+ status = p_->tree . tickExactlyOnce ();
217212
218213 if (const auto res = onLoopAfterTick (status); res.has_value ())
219214 {
@@ -232,7 +227,7 @@ void TreeExecutionServer::execute(
232227 const auto now = std::chrono::steady_clock::now ();
233228 if (now < loop_deadline)
234229 {
235- p_->tree -> sleep (loop_deadline - now);
230+ p_->tree . sleep (loop_deadline - now);
236231 }
237232 loop_deadline += period;
238233 }
@@ -245,19 +240,32 @@ void TreeExecutionServer::execute(
245240 return ;
246241 }
247242
248- // set the node_status result to the action
249- action_result->node_status = ConvertNodeStatus (status);
250-
251243 // Call user defined onTreeExecutionCompleted function.
252244 // Override the message value if the user defined function returns it
253245 if (auto msg = onTreeExecutionCompleted (status, false ))
254246 {
255247 action_result->return_message = msg.value ();
256248 }
249+ else
250+ {
251+ action_result->return_message =
252+ std::string (" Tree finished with status: " ) + BT::toStr (status);
253+ }
254+
255+ // set the node_status result to the action
256+ action_result->node_status = ConvertNodeStatus (status);
257257
258258 // return success or aborted for the action result
259- RCLCPP_INFO (kLogger , " BT finished with status: %s" , BT::toStr (status).c_str ());
260- goal_handle->succeed (action_result);
259+ if (status == BT::NodeStatus::SUCCESS)
260+ {
261+ RCLCPP_INFO (kLogger , action_result->return_message .c_str ());
262+ goal_handle->succeed (action_result);
263+ }
264+ else
265+ {
266+ RCLCPP_ERROR (kLogger , action_result->return_message .c_str ());
267+ goal_handle->abort (action_result);
268+ }
261269}
262270
263271const std::string& TreeExecutionServer::treeName () const
@@ -270,9 +278,9 @@ const std::string& TreeExecutionServer::goalPayload() const
270278 return p_->payload ;
271279}
272280
273- BT::Tree* TreeExecutionServer::tree ()
281+ const BT::Tree& TreeExecutionServer::tree () const
274282{
275- return p_->tree ? p_-> tree . get () : nullptr ;
283+ return p_->tree ;
276284}
277285
278286BT::Blackboard::Ptr TreeExecutionServer::globalBlackboard ()
0 commit comments