AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
ros_action_node.hpp
1// Copyright 2024 Robin Müller
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// https://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#pragma once
16
17#include <chrono>
18#include <memory>
19#include <string>
20
21#include "action_msgs/srv/cancel_goal.hpp"
22#include "auto_apms_behavior_tree_core/exceptions.hpp"
23#include "auto_apms_behavior_tree_core/node/ros_node_context.hpp"
24#include "auto_apms_util/string.hpp"
25#include "behaviortree_cpp/action_node.h"
26#include "rclcpp/executors.hpp"
27#include "rclcpp_action/rclcpp_action.hpp"
28
30{
31
32enum ActionNodeErrorCode
33{
34 SERVER_UNREACHABLE,
35 SEND_GOAL_TIMEOUT,
36 GOAL_REJECTED_BY_SERVER,
37 INVALID_GOAL
38};
39
45inline const char * toStr(const ActionNodeErrorCode & err)
46{
47 switch (err) {
48 case SERVER_UNREACHABLE:
49 return "SERVER_UNREACHABLE";
50 case SEND_GOAL_TIMEOUT:
51 return "SEND_GOAL_TIMEOUT";
52 case GOAL_REJECTED_BY_SERVER:
53 return "GOAL_REJECTED_BY_SERVER";
54 case INVALID_GOAL:
55 return "INVALID_GOAL";
56 }
57 return nullptr;
58}
59
96template <class ActionT>
97class RosActionNode : public BT::ActionNodeBase
98{
99 using ActionClient = typename rclcpp_action::Client<ActionT>;
100 using ActionClientPtr = std::shared_ptr<ActionClient>;
101 using GoalHandle = typename rclcpp_action::ClientGoalHandle<ActionT>;
102
103 struct ActionClientInstance
104 {
105 ActionClientInstance(
106 rclcpp::Node::SharedPtr node, rclcpp::CallbackGroup::SharedPtr group, const std::string & action_name);
107
108 ActionClientPtr action_client;
109 std::string name;
110 };
111
112 using ClientsRegistry = std::unordered_map<std::string, std::weak_ptr<ActionClientInstance>>;
113
114public:
115 using ActionType = ActionT;
116 using Goal = typename ActionT::Goal;
117 using Feedback = typename ActionT::Feedback;
118 using WrappedResult = typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult;
119 using Config = BT::NodeConfig;
120 using Context = RosNodeContext;
121
131 explicit RosActionNode(const std::string & instance_name, const Config & config, Context context);
132
133 virtual ~RosActionNode() = default;
134
142 static BT::PortsList providedBasicPorts(BT::PortsList addition)
143 {
144 BT::PortsList basic = {BT::InputPort<std::string>("port", "Name of the ROS 2 action.")};
145 basic.insert(addition.begin(), addition.end());
146 return basic;
147 }
148
153 static BT::PortsList providedPorts() { return providedBasicPorts({}); }
154
162 virtual void onHalt();
163
173 virtual bool setGoal(Goal & goal);
174
185 virtual BT::NodeStatus onResultReceived(const WrappedResult & result);
186
197 virtual BT::NodeStatus onFeedback(const Feedback & feedback);
198
208 virtual BT::NodeStatus onFailure(ActionNodeErrorCode error);
209
216
222 bool createClient(const std::string & action_name);
223
228 std::string getActionName() const;
229
230protected:
231 const Context context_;
232 const rclcpp::Logger logger_;
233
234private:
235 void halt() override;
236
237 BT::NodeStatus tick() override;
238
239 static std::mutex & getMutex();
240
241 // contains the fully-qualified name of the node and the name of the client
242 static ClientsRegistry & getRegistry();
243
244 bool dynamic_client_instance_ = false;
245 std::shared_ptr<ActionClientInstance> client_instance_;
246 std::string action_client_key_;
247 std::shared_future<typename GoalHandle::SharedPtr> future_goal_handle_;
248 typename GoalHandle::SharedPtr goal_handle_;
249 rclcpp::Time time_goal_sent_;
250 BT::NodeStatus on_feedback_state_change_;
251 bool goal_response_received_; // We must use this additional flag because goal_handle_ may be nullptr if rejected
252 bool goal_rejected_;
253 bool result_received_;
254 bool cancel_requested_;
255 WrappedResult result_;
256};
257
258// #####################################################################################################################
259// ################################ DEFINITIONS ##############################################
260// #####################################################################################################################
261
262template <class ActionT>
263RosActionNode<ActionT>::ActionClientInstance::ActionClientInstance(
264 rclcpp::Node::SharedPtr node, rclcpp::CallbackGroup::SharedPtr group, const std::string & action_name)
265{
266 action_client = rclcpp_action::create_client<ActionT>(node, action_name, group);
267 name = action_name;
268}
269
270template <class ActionT>
271inline RosActionNode<ActionT>::RosActionNode(const std::string & instance_name, const Config & config, Context context)
272: BT::ActionNodeBase(instance_name, config),
273 context_(context),
274 logger_(context.getChildLogger(auto_apms_util::toSnakeCase(instance_name)))
275{
276 if (const BT::Expected<std::string> expected_name = context_.getCommunicationPortName(this)) {
277 createClient(expected_name.value());
278 } else {
279 // We assume that determining the communication port requires a blackboard pointer, which cannot be evaluated at
280 // construction time. The expression will be evaluated each time before the node is ticked the first time after
281 // successful execution.
282 dynamic_client_instance_ = true;
283 }
284}
285
286template <class ActionT>
288{
289}
290
291template <class ActionT>
292inline bool RosActionNode<ActionT>::setGoal(Goal & /*goal*/)
293{
294 return true;
295}
296
297template <class ActionT>
298inline BT::NodeStatus RosActionNode<ActionT>::onResultReceived(const WrappedResult & result)
299{
300 std::string result_str;
301 switch (result.code) {
302 case rclcpp_action::ResultCode::ABORTED:
303 result_str = "ABORTED";
304 break;
305 case rclcpp_action::ResultCode::CANCELED:
306 result_str = "CANCELED";
307 break;
308 case rclcpp_action::ResultCode::SUCCEEDED:
309 result_str = "SUCCEEDED";
310 break;
311 case rclcpp_action::ResultCode::UNKNOWN:
312 result_str = "UNKNOWN";
313 break;
314 }
315 RCLCPP_DEBUG(
316 logger_, "%s - Goal completed. Received result %s.", context_.getFullyQualifiedTreeNodeName(this).c_str(),
317 result_str.c_str());
318 if (result.code == rclcpp_action::ResultCode::SUCCEEDED) return BT::NodeStatus::SUCCESS;
319 if (cancel_requested_ && result.code == rclcpp_action::ResultCode::CANCELED) return BT::NodeStatus::SUCCESS;
320 return BT::NodeStatus::FAILURE;
321}
322
323template <class ActionT>
324inline BT::NodeStatus RosActionNode<ActionT>::onFeedback(const Feedback & /*feedback*/)
325{
326 return BT::NodeStatus::RUNNING;
327}
328
329template <class ActionT>
330inline BT::NodeStatus RosActionNode<ActionT>::onFailure(ActionNodeErrorCode error)
331{
332 const std::string msg = context_.getFullyQualifiedTreeNodeName(this) + " - Unexpected error " +
333 std::to_string(error) + ": " + toStr(error) + ".";
334 RCLCPP_ERROR_STREAM(logger_, msg);
335 throw exceptions::RosNodeError(msg);
336}
337
338template <class T>
340{
341 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_ptr = context_.executor_.lock();
342 if (!executor_ptr) {
343 throw exceptions::RosNodeError(
344 context_.getFullyQualifiedTreeNodeName(this) + " - Cannot cancel goal for action '" + client_instance_->name +
345 "' since the pointer to the associated ROS 2 executor expired.");
346 }
347
348 if (future_goal_handle_.valid()) {
349 RCLCPP_DEBUG(
350 logger_, "%s - Awaiting goal response before trying to cancel goal...",
351 context_.getFullyQualifiedTreeNodeName(this).c_str());
352 // Here the discussion is if we should block or put a timer for the waiting
353 const rclcpp::FutureReturnCode ret =
354 executor_ptr->spin_until_future_complete(future_goal_handle_, context_.registration_options_.request_timeout);
355 if (ret != rclcpp::FutureReturnCode::SUCCESS) {
356 // Do nothing in case of INTERRUPT or TIMEOUT
357 return;
358 }
359 goal_handle_ = future_goal_handle_.get();
360 future_goal_handle_ = {};
361 goal_rejected_ = goal_handle_ == nullptr;
362 }
363
364 // If goal was rejected or handle has been invalidated, we do not need to cancel
365 if (goal_rejected_) {
366 RCLCPP_DEBUG(
367 logger_, "%s - Goal was rejected. Nothing to cancel.", context_.getFullyQualifiedTreeNodeName(this).c_str());
368 return;
369 };
370
371 // If goal was accepted, but goal handle is nullptr, result callback was already called which means that the goal has
372 // already reached a terminal state
373 if (!goal_handle_) {
374 RCLCPP_DEBUG(
375 logger_, "%s - Goal has already reached a terminal state. Nothing to cancel.",
376 context_.getFullyQualifiedTreeNodeName(this).c_str());
377 return;
378 };
379
380 const std::string uuid_str = rclcpp_action::to_string(goal_handle_->get_goal_id());
381 RCLCPP_DEBUG(
382 logger_, "%s - Canceling goal %s for action '%s'.", context_.getFullyQualifiedTreeNodeName(this).c_str(),
383 uuid_str.c_str(), client_instance_->name.c_str());
384
385 // Send the cancellation request
386 std::shared_future<std::shared_ptr<typename ActionClient::CancelResponse>> future_cancel_response =
387 client_instance_->action_client->async_cancel_goal(goal_handle_);
388 if (const auto code = executor_ptr->spin_until_future_complete(
389 future_cancel_response, context_.registration_options_.request_timeout);
390 code != rclcpp::FutureReturnCode::SUCCESS) {
391 RCLCPP_WARN(
392 logger_, "%s - Failed to wait for response for cancellation request (Code: %s).",
393 context_.getFullyQualifiedTreeNodeName(this).c_str(), rclcpp::to_string(code).c_str());
394
395 // Make sure goal handle is invalidated
396 goal_handle_ = nullptr;
397 return;
398 }
399
400 // Check the response for the cancellation request
401 if (!future_cancel_response.get()) {
402 throw std::logic_error("Shared pointer to cancel response is nullptr.");
403 }
404 typename ActionClient::CancelResponse cancel_response = *future_cancel_response.get();
405 std::string cancel_response_str;
406 switch (cancel_response.return_code) {
407 case action_msgs::srv::CancelGoal::Response::ERROR_REJECTED:
408 cancel_response_str = "ERROR_REJECTED";
409 break;
410 case action_msgs::srv::CancelGoal::Response::ERROR_UNKNOWN_GOAL_ID:
411 cancel_response_str = "ERROR_UNKNOWN_GOAL_ID";
412 break;
413 case action_msgs::srv::CancelGoal::Response::ERROR_GOAL_TERMINATED:
414 cancel_response_str = "ERROR_GOAL_TERMINATED";
415 break;
416 default:
417 cancel_response_str = "ERROR_NONE";
418 break;
419 }
420 if (cancel_response.return_code == action_msgs::srv::CancelGoal::Response::ERROR_NONE) {
421 RCLCPP_DEBUG(
422 logger_,
423 "%s - Cancellation request of goal %s for action '%s' was accepted (Response: %s). Awaiting completion...",
424 context_.getFullyQualifiedTreeNodeName(this).c_str(),
425 rclcpp_action::to_string(goal_handle_->get_goal_id()).c_str(), client_instance_->name.c_str(),
426 cancel_response_str.c_str());
427
428 // Wait for the cancellation to be complete (goal result received)
429 std::shared_future<WrappedResult> future_goal_result =
430 client_instance_->action_client->async_get_result(goal_handle_);
431 if (const auto code =
432 executor_ptr->spin_until_future_complete(future_goal_result, context_.registration_options_.request_timeout);
433 code == rclcpp::FutureReturnCode::SUCCESS) {
434 RCLCPP_DEBUG(
435 logger_, "%s - Goal %s for action '%s' was cancelled successfully.",
436 context_.getFullyQualifiedTreeNodeName(this).c_str(), uuid_str.c_str(), client_instance_->name.c_str());
437 } else {
438 RCLCPP_WARN(
439 logger_, "%s - Failed to wait until cancellation completed (Code: %s).",
440 context_.getFullyQualifiedTreeNodeName(this).c_str(), rclcpp::to_string(code).c_str());
441 }
442 } else {
443 // The cancellation request was rejected. If this was due to the goal having terminated normally before the request
444 // was processed by the server, we consider the cancellation as a success. Otherwise we warn.
445 if (cancel_response.return_code == action_msgs::srv::CancelGoal::Response::ERROR_GOAL_TERMINATED) {
446 RCLCPP_DEBUG(
447 logger_, "%s - Goal %s for action '%s' has already terminated (Response: %s). Nothing to cancel.",
448 context_.getFullyQualifiedTreeNodeName(this).c_str(), uuid_str.c_str(), client_instance_->name.c_str(),
449 cancel_response_str.c_str());
450 } else {
451 RCLCPP_WARN(
452 logger_, "%s - Cancellation request was rejected (Response: %s).",
453 context_.getFullyQualifiedTreeNodeName(this).c_str(), cancel_response_str.c_str());
454 }
455 }
456
457 // Make sure goal handle is invalidated
458 goal_handle_ = nullptr;
459}
460
461template <class T>
462inline void RosActionNode<T>::halt()
463{
464 if (status() == BT::NodeStatus::RUNNING) {
465 cancel_requested_ = true;
466 onHalt();
467 cancelGoal();
468 resetStatus();
469 }
470}
471
472template <class T>
473inline BT::NodeStatus RosActionNode<T>::tick()
474{
475 if (!rclcpp::ok()) {
476 halt();
477 throw exceptions::RosNodeError(
478 context_.getFullyQualifiedTreeNodeName(this) + " - ROS 2 context has been shut down.");
479 }
480
481 // If client has been set up in derived constructor, event though this constructor couldn't, we discard the intention
482 // of dynamically creating the client
483 if (dynamic_client_instance_ && client_instance_) {
484 dynamic_client_instance_ = false;
485 }
486
487 // Try again to create the client on first tick if this was not possible during construction or if client should be
488 // created from a blackboard entry on the start of every iteration
489 if (status() == BT::NodeStatus::IDLE && dynamic_client_instance_) {
490 const BT::Expected<std::string> expected_name = context_.getCommunicationPortName(this);
491 if (expected_name) {
492 createClient(expected_name.value());
493 } else {
494 throw exceptions::RosNodeError(
495 context_.getFullyQualifiedTreeNodeName(this) +
496 " - Cannot create the action client because the action name couldn't be resolved using "
497 "the communication port expression specified by the node's "
498 "registration parameters (" +
499 NodeRegistrationOptions::PARAM_NAME_PORT + ": " + context_.registration_options_.port +
500 "). Error message: " + expected_name.error());
501 }
502 }
503
504 if (!client_instance_) {
505 throw exceptions::RosNodeError(context_.getFullyQualifiedTreeNodeName(this) + " - client_instance_ is nullptr.");
506 }
507
508 auto & action_client = client_instance_->action_client;
509
510 //------------------------------------------
511 auto check_status = [this](BT::NodeStatus status) {
512 if (!isStatusCompleted(status)) {
513 throw exceptions::RosNodeError(
514 context_.getFullyQualifiedTreeNodeName(this) + " - The callback must return either SUCCESS or FAILURE.");
515 }
516 return status;
517 };
518
519 // first step to be done only at the beginning of the Action
520 if (status() == BT::NodeStatus::IDLE) {
521 setStatus(BT::NodeStatus::RUNNING);
522
523 goal_response_received_ = false;
524 goal_rejected_ = false;
525 result_received_ = false;
526 cancel_requested_ = false;
527 on_feedback_state_change_ = BT::NodeStatus::RUNNING;
528 result_ = {};
529
530 // Check if server is ready
531 if (!action_client->action_server_is_ready()) {
532 return onFailure(SERVER_UNREACHABLE);
533 }
534
535 Goal goal;
536 if (!setGoal(goal)) {
537 return check_status(onFailure(INVALID_GOAL));
538 }
539
540 typename ActionClient::SendGoalOptions goal_options;
541 goal_options.goal_response_callback = [this](typename GoalHandle::SharedPtr goal_handle) {
542 // Indicate that a goal response has been received and let tick() do the rest
543 this->goal_response_received_ = true;
544 this->goal_rejected_ = goal_handle == nullptr;
545 this->goal_handle_ = goal_handle;
546 };
547 goal_options.feedback_callback =
548 [this](typename GoalHandle::SharedPtr /*goal_handle*/, const std::shared_ptr<const Feedback> feedback) {
549 this->on_feedback_state_change_ = onFeedback(*feedback);
550 if (this->on_feedback_state_change_ == BT::NodeStatus::IDLE) {
551 throw std::logic_error(
552 this->context_.getFullyQualifiedTreeNodeName(this) + " - onFeedback() must not return IDLE.");
553 }
554 this->emitWakeUpSignal();
555 };
556 goal_options.result_callback = [this](const WrappedResult & result) {
557 // The result callback is also invoked when goal is rejected (code: CANCELED), but we only want to call
558 // onResultReceived if the goal was accepted and we want to return prematurely. Therefore, we use the
559 // cancel_requested_ flag.
560 if (this->cancel_requested_) {
561 // If the node is to return prematurely, we must invoke onResultReceived here. The returned status has no effect
562 // in this case.
563 this->onResultReceived(result);
564 }
565 this->result_received_ = true;
566 this->goal_handle_ = nullptr; // Reset internal goal handle when result was received
567 this->result_ = result;
568 this->emitWakeUpSignal();
569 };
570
571 future_goal_handle_ = action_client->async_send_goal(goal, goal_options);
572 time_goal_sent_ = context_.getCurrentTime();
573 return BT::NodeStatus::RUNNING;
574 }
575
576 if (status() == BT::NodeStatus::RUNNING) {
577 std::unique_lock<std::mutex> lock(getMutex());
578
579 // FIRST case: check if the goal request has a timeout as long as goal_response_received_ is false (Is set to true
580 // as soon as a goal response is received)
581 if (!goal_response_received_) {
582 // See if we must time out
583 if ((context_.getCurrentTime() - time_goal_sent_) > context_.registration_options_.request_timeout) {
584 return check_status(onFailure(SEND_GOAL_TIMEOUT));
585 }
586 return BT::NodeStatus::RUNNING;
587 } else if (future_goal_handle_.valid()) {
588 // We noticed, that a goal response has just been received and have to prepare the next steps now
589 future_goal_handle_ = {}; // Invalidate future since it's obsolete now and it indicates that we've done this step
590
591 if (goal_rejected_) return check_status(onFailure(GOAL_REJECTED_BY_SERVER));
592 RCLCPP_DEBUG(
593 logger_, "%s - Goal %s accepted by server, waiting for result.",
594 context_.getFullyQualifiedTreeNodeName(this).c_str(),
595 rclcpp_action::to_string(goal_handle_->get_goal_id()).c_str());
596 }
597
598 // SECOND case: onFeedback requested a stop
599 if (on_feedback_state_change_ != BT::NodeStatus::RUNNING) {
600 cancel_requested_ = true;
601 cancelGoal();
602 return on_feedback_state_change_;
603 }
604
605 // THIRD case: result received
606 if (result_received_) {
607 return check_status(onResultReceived(result_));
608 }
609 }
610 return BT::NodeStatus::RUNNING;
611}
612
613template <class ActionT>
614inline bool RosActionNode<ActionT>::createClient(const std::string & action_name)
615{
616 if (action_name.empty()) {
617 throw exceptions::RosNodeError(
618 context_.getFullyQualifiedTreeNodeName(this) +
619 " - Argument action_name is empty when trying to create the client.");
620 }
621
622 // Check if the action with given name is already set up
623 if (
624 client_instance_ && action_name == client_instance_->name &&
625 client_instance_->action_client->action_server_is_ready()) {
626 return true;
627 }
628
629 std::unique_lock lk(getMutex());
630
631 rclcpp::Node::SharedPtr node = context_.nh_.lock();
632 if (!node) {
633 throw exceptions::RosNodeError(
634 context_.getFullyQualifiedTreeNodeName(this) +
635 " - The weak pointer to the ROS 2 node expired. The tree node doesn't "
636 "take ownership of it.");
637 }
638 rclcpp::CallbackGroup::SharedPtr group = context_.cb_group_.lock();
639 if (!group) {
640 throw exceptions::RosNodeError(
641 context_.getFullyQualifiedTreeNodeName(this) +
642 " - The weak pointer to the ROS 2 callback group expired. The tree node doesn't "
643 "take ownership of it.");
644 }
645 action_client_key_ = std::string(node->get_fully_qualified_name()) + "/" + action_name;
646
647 auto & registry = getRegistry();
648 auto it = registry.find(action_client_key_);
649 if (it == registry.end() || it->second.expired()) {
650 client_instance_ = std::make_shared<ActionClientInstance>(node, group, action_name);
651 registry.insert({action_client_key_, client_instance_});
652 RCLCPP_DEBUG(
653 logger_, "%s - Created client for action '%s'.", context_.getFullyQualifiedTreeNodeName(this).c_str(),
654 action_name.c_str());
655 } else {
656 client_instance_ = it->second.lock();
657 }
658
659 bool found = client_instance_->action_client->wait_for_action_server(context_.registration_options_.wait_timeout);
660 if (!found) {
661 std::string msg = context_.getFullyQualifiedTreeNodeName(this) + " - Action server with name '" +
662 client_instance_->name + "' is not reachable.";
663 if (context_.registration_options_.allow_unreachable) {
664 RCLCPP_WARN_STREAM(logger_, msg);
665 } else {
666 RCLCPP_ERROR_STREAM(logger_, msg);
667 throw exceptions::RosNodeError(msg);
668 }
669 }
670 return found;
671}
672
673template <class ActionT>
675{
676 if (client_instance_) return client_instance_->name;
677 return "unkown";
678}
679
680template <class ActionT>
681inline std::mutex & RosActionNode<ActionT>::getMutex()
682{
683 static std::mutex action_client_mutex;
684 return action_client_mutex;
685}
686
687template <class ActionT>
688inline typename RosActionNode<ActionT>::ClientsRegistry & RosActionNode<ActionT>::getRegistry()
689{
690 static ClientsRegistry action_clients_registry;
691 return action_clients_registry;
692}
693
694} // namespace auto_apms_behavior_tree::core
virtual BT::NodeStatus onFeedback(const Feedback &feedback)
Callback invoked after action feedback was received.
virtual void onHalt()
Callback invoked when the node is halted by the behavior tree.
virtual bool setGoal(Goal &goal)
Set the goal message to be sent to the ROS 2 action.
RosActionNode(const std::string &instance_name, const Config &config, Context context)
Constructor.
virtual BT::NodeStatus onFailure(ActionNodeErrorCode error)
Callback invoked when one of the errors in ActionNodeErrorCode occur.
void cancelGoal()
Synchronous method that sends a request to the server to cancel the current action.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
Derived nodes implementing the static method RosActionNode::providedPorts may call this method to als...
bool createClient(const std::string &action_name)
Create the client of the ROS 2 action.
virtual BT::NodeStatus onResultReceived(const WrappedResult &result)
Callback invoked after the result that is sent by the action server when the goal terminated was rece...
static BT::PortsList providedPorts()
If a behavior tree requires input/output data ports, the developer must define this method accordingl...
std::string getActionName() const
Get the name of the action this node connects with.
Additional parameters specific to ROS 2 determined at runtime by TreeBuilder.
Core API for AutoAPMS's behavior tree implementation.
Definition builder.hpp:30
const char * toStr(const ActionNodeErrorCode &err)
Convert the action error code to string.
Fundamental helper classes and utility functions.