231 const Context context_;
232 const rclcpp::Logger logger_;
235 void halt()
override;
237 BT::NodeStatus tick()
override;
239 static std::mutex & getMutex();
242 static ClientsRegistry & getRegistry();
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_;
253 bool result_received_;
254 bool cancel_requested_;
255 WrappedResult result_;
262template <
class ActionT>
263RosActionNode<ActionT>::ActionClientInstance::ActionClientInstance(
264 rclcpp::Node::SharedPtr node, rclcpp::CallbackGroup::SharedPtr group,
const std::string & action_name)
266 action_client = rclcpp_action::create_client<ActionT>(node, action_name, group);
270template <
class ActionT>
272: BT::ActionNodeBase(instance_name, config),
274 logger_(context.getChildLogger(
auto_apms_util::toSnakeCase(instance_name)))
276 if (
const BT::Expected<std::string> expected_name = context_.getCommunicationPortName(
this)) {
277 createClient(expected_name.value());
282 dynamic_client_instance_ = true;
286template <
class ActionT>
291template <
class ActionT>
297template <
class ActionT>
300 std::string result_str;
301 switch (result.code) {
302 case rclcpp_action::ResultCode::ABORTED:
303 result_str =
"ABORTED";
305 case rclcpp_action::ResultCode::CANCELED:
306 result_str =
"CANCELED";
308 case rclcpp_action::ResultCode::SUCCEEDED:
309 result_str =
"SUCCEEDED";
311 case rclcpp_action::ResultCode::UNKNOWN:
312 result_str =
"UNKNOWN";
316 logger_,
"%s - Goal completed. Received result %s.", context_.getFullyQualifiedTreeNodeName(
this).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;
323template <
class ActionT>
326 return BT::NodeStatus::RUNNING;
329template <
class ActionT>
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);
341 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_ptr = context_.executor_.lock();
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.");
348 if (future_goal_handle_.valid()) {
350 logger_,
"%s - Awaiting goal response before trying to cancel goal...",
351 context_.getFullyQualifiedTreeNodeName(
this).c_str());
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) {
359 goal_handle_ = future_goal_handle_.get();
360 future_goal_handle_ = {};
361 goal_rejected_ = goal_handle_ ==
nullptr;
365 if (goal_rejected_) {
367 logger_,
"%s - Goal was rejected. Nothing to cancel.", context_.getFullyQualifiedTreeNodeName(
this).c_str());
375 logger_,
"%s - Goal has already reached a terminal state. Nothing to cancel.",
376 context_.getFullyQualifiedTreeNodeName(
this).c_str());
380 const std::string uuid_str = rclcpp_action::to_string(goal_handle_->get_goal_id());
382 logger_,
"%s - Canceling goal %s for action '%s'.", context_.getFullyQualifiedTreeNodeName(
this).c_str(),
383 uuid_str.c_str(), client_instance_->name.c_str());
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) {
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());
396 goal_handle_ =
nullptr;
401 if (!future_cancel_response.get()) {
402 throw std::logic_error(
"Shared pointer to cancel response is nullptr.");
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";
410 case action_msgs::srv::CancelGoal::Response::ERROR_UNKNOWN_GOAL_ID:
411 cancel_response_str =
"ERROR_UNKNOWN_GOAL_ID";
413 case action_msgs::srv::CancelGoal::Response::ERROR_GOAL_TERMINATED:
414 cancel_response_str =
"ERROR_GOAL_TERMINATED";
417 cancel_response_str =
"ERROR_NONE";
420 if (cancel_response.return_code == action_msgs::srv::CancelGoal::Response::ERROR_NONE) {
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());
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) {
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());
439 logger_,
"%s - Failed to wait until cancellation completed (Code: %s).",
440 context_.getFullyQualifiedTreeNodeName(
this).c_str(), rclcpp::to_string(code).c_str());
445 if (cancel_response.return_code == action_msgs::srv::CancelGoal::Response::ERROR_GOAL_TERMINATED) {
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());
452 logger_,
"%s - Cancellation request was rejected (Response: %s).",
453 context_.getFullyQualifiedTreeNodeName(
this).c_str(), cancel_response_str.c_str());
458 goal_handle_ =
nullptr;
462inline void RosActionNode<T>::halt()
464 if (status() == BT::NodeStatus::RUNNING) {
465 cancel_requested_ =
true;
473inline BT::NodeStatus RosActionNode<T>::tick()
477 throw exceptions::RosNodeError(
478 context_.getFullyQualifiedTreeNodeName(
this) +
" - ROS 2 context has been shut down.");
483 if (dynamic_client_instance_ && client_instance_) {
484 dynamic_client_instance_ =
false;
489 if (status() == BT::NodeStatus::IDLE && dynamic_client_instance_) {
490 const BT::Expected<std::string> expected_name = context_.getCommunicationPortName(
this);
492 createClient(expected_name.value());
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());
504 if (!client_instance_) {
505 throw exceptions::RosNodeError(context_.getFullyQualifiedTreeNodeName(
this) +
" - client_instance_ is nullptr.");
508 auto & action_client = client_instance_->action_client;
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.");
520 if (status() == BT::NodeStatus::IDLE) {
521 setStatus(BT::NodeStatus::RUNNING);
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;
531 if (!action_client->action_server_is_ready()) {
532 return onFailure(SERVER_UNREACHABLE);
536 if (!setGoal(goal)) {
537 return check_status(onFailure(INVALID_GOAL));
540 typename ActionClient::SendGoalOptions goal_options;
541 goal_options.goal_response_callback = [
this](
typename GoalHandle::SharedPtr goal_handle) {
543 this->goal_response_received_ =
true;
544 this->goal_rejected_ = goal_handle ==
nullptr;
545 this->goal_handle_ = goal_handle;
547 goal_options.feedback_callback =
548 [
this](
typename GoalHandle::SharedPtr ,
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.");
554 this->emitWakeUpSignal();
556 goal_options.result_callback = [
this](
const WrappedResult & result) {
560 if (this->cancel_requested_) {
563 this->onResultReceived(result);
565 this->result_received_ =
true;
566 this->goal_handle_ =
nullptr;
567 this->result_ = result;
568 this->emitWakeUpSignal();
571 future_goal_handle_ = action_client->async_send_goal(goal, goal_options);
572 time_goal_sent_ = context_.getCurrentTime();
573 return BT::NodeStatus::RUNNING;
576 if (status() == BT::NodeStatus::RUNNING) {
577 std::unique_lock<std::mutex> lock(getMutex());
581 if (!goal_response_received_) {
583 if ((context_.getCurrentTime() - time_goal_sent_) > context_.registration_options_.request_timeout) {
584 return check_status(onFailure(SEND_GOAL_TIMEOUT));
586 return BT::NodeStatus::RUNNING;
587 }
else if (future_goal_handle_.valid()) {
589 future_goal_handle_ = {};
591 if (goal_rejected_)
return check_status(onFailure(GOAL_REJECTED_BY_SERVER));
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());
599 if (on_feedback_state_change_ != BT::NodeStatus::RUNNING) {
600 cancel_requested_ =
true;
602 return on_feedback_state_change_;
606 if (result_received_) {
607 return check_status(onResultReceived(result_));
610 return BT::NodeStatus::RUNNING;
613template <
class ActionT>
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.");
624 client_instance_ && action_name == client_instance_->name &&
625 client_instance_->action_client->action_server_is_ready()) {
629 std::unique_lock lk(getMutex());
631 rclcpp::Node::SharedPtr node = context_.nh_.lock();
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.");
638 rclcpp::CallbackGroup::SharedPtr group = context_.cb_group_.lock();
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.");
645 action_client_key_ = std::string(node->get_fully_qualified_name()) +
"/" + action_name;
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_});
653 logger_,
"%s - Created client for action '%s'.", context_.getFullyQualifiedTreeNodeName(
this).c_str(),
654 action_name.c_str());
656 client_instance_ = it->second.lock();
659 bool found = client_instance_->action_client->wait_for_action_server(context_.registration_options_.wait_timeout);
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);
666 RCLCPP_ERROR_STREAM(logger_, msg);
667 throw exceptions::RosNodeError(msg);
673template <
class ActionT>
676 if (client_instance_)
return client_instance_->name;