BehaviorTree / BehaviorTree.ROS2

BehaviorTree.CPP utilities to work with ROS2
Apache License 2.0
144 stars 59 forks source link

Cancellation of unkown goal not detectable #57

Closed robin-mueller closed 4 months ago

robin-mueller commented 4 months ago

Hi, I wanted to note that it can be desirable to throw rclcpp_action::exceptions::UnknownGoalHandleError or at least any kind of exception on cancelGoal() if the goal response has not arrived yet. In fact, I am relying on such a case in my application, because I want to make sure that the goal is canceled either way, so I wait until it has arrived and proceed with the cancellation. After merging #53, there is no way for me to detect if haltTree() ran into a problem or not. Before I did like below:

try {
  tree.haltTree();
} catch (const rclcpp_action::exceptions::UnknownGoalHandleError& e) {
    // If tree is halted directly after an action started, the goal response might not have been
    // received yet. In this case we assume the goal is about to arrive and asynchronously retry to HALT
}

I have a seperate ROS2 node that tries to halt the tree and doesn't know about when a RosActionNode published goal requests, so it is mandatory for this case to be detectable during halting the tree.

I am falling back to a previous commit, until this issue has been resolved.

Originally posted by @robin-mueller in https://github.com/BehaviorTree/BehaviorTree.ROS2/issues/53#issuecomment-2067806301

vicmassy commented 4 months ago

probably here the approach would be to try to cancel the goal if it was sent but not accepted yet. I also share what @facontidavide said here about not throwing errors which is quite undesirable normally.

This is the current code:

if (!goal_handle_)
  {
    RCLCPP_WARN( node_->get_logger(), "cancelGoal called on an empty goal_handle");
    return;
  }

and it could be changed to something like this:

if (!goal_handle_)
  {
   if (future_goal_handle_) {
     // Here the discussion is if we should block or put a timer for the waiting
     auto ret = callback_group_executor_.spin_until_future_complete(future_goal_handle_, timeout);
     if (ret != rclcpp::FutureReturnCode::SUCCESS) {
        return;
        // In that case the goal was not accepted or timed out so probably we should do nothing.
      }
      else {
        goal_handle_ = future_goal_handle_.get();   
      }
    } else {
       RCLCPP_WARN( node_->get_logger(), "cancelGoal called on an empty goal_handle");
       return;
   }
  }
robin-mueller commented 4 months ago

This change would correspond to behavior B in my suggestion of possible changes: Wait for the goal response during halt().

An implementation like this is entirely fine, but just as I said in the linked comment, it probably is more intuitive if we wait for the goal response during the initial tick (Behavior A). I understand that one wouldn't want to block for too long, but it still is a RosActionNode, not a RosWaitForResponseNode. At least, I think that this behavior should be configurable.

facontidavide commented 4 months ago

I will adapt this change for the time being and decide later if there is any better alternative.

robin-mueller commented 3 months ago

I am sorry to come back on this, but it turns out that the current code still doesn't work correctly:

if goal_handle_ has been set due to a previous incoming goal response, the variable is never reset to nullptr when this goal terminates. Now, if a subsequent goal is requested and the original issue occurs, goal_handle_ evaluates as true and yet another rclcpp_action::UnknownGoalError is thrown, although due to a different reason.

I suggest to do goal_handle_ = nullptr after a new goal is accepted or change the implementation in favor of behavior A.