Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add the ability for ros actions nodes to get access to the action result even on failure #79

Open
wants to merge 1 commit into
base: humble
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 13 additions & 5 deletions behaviortree_ros2/include/behaviortree_ros2/bt_action_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <memory>
#include <string>
#include <optional>
#include <rclcpp/executors.hpp>
#include <rclcpp/allocator/allocator_common.hpp>
#include "behaviortree_cpp/action_node.h"
Expand Down Expand Up @@ -152,8 +153,15 @@ class RosActionNode : public BT::ActionNodeBase
}

/** Callback invoked when something goes wrong.
* The result is provided if it is available.
* It must return either SUCCESS or FAILURE.
*/
virtual BT::NodeStatus onFailure(ActionNodeErrorCode error,
const std::optional<WrappedResult>&)
{
return onFailure(error);
}

virtual BT::NodeStatus onFailure(ActionNodeErrorCode /*error*/)
{
return NodeStatus::FAILURE;
Expand Down Expand Up @@ -390,7 +398,7 @@ inline NodeStatus RosActionNode<T>::tick()

if(!setGoal(goal))
{
return CheckStatus(onFailure(INVALID_GOAL));
return CheckStatus(onFailure(INVALID_GOAL, {}));
}

typename ActionClient::SendGoalOptions goal_options;
Expand Down Expand Up @@ -432,7 +440,7 @@ inline NodeStatus RosActionNode<T>::tick()
// Check if server is ready
if(!action_client->action_server_is_ready())
{
return onFailure(SERVER_UNREACHABLE);
return onFailure(SERVER_UNREACHABLE, {});
}

future_goal_handle_ = action_client->async_send_goal(goal, goal_options);
Expand All @@ -459,7 +467,7 @@ inline NodeStatus RosActionNode<T>::tick()
{
if((now() - time_goal_sent_) > timeout)
{
return CheckStatus(onFailure(SEND_GOAL_TIMEOUT));
return CheckStatus(onFailure(SEND_GOAL_TIMEOUT, {}));
}
else
{
Expand Down Expand Up @@ -490,11 +498,11 @@ inline NodeStatus RosActionNode<T>::tick()
{
if(result_.code == rclcpp_action::ResultCode::ABORTED)
{
return CheckStatus(onFailure(ACTION_ABORTED));
return CheckStatus(onFailure(ACTION_ABORTED, result_));
}
else if(result_.code == rclcpp_action::ResultCode::CANCELED)
{
return CheckStatus(onFailure(ACTION_CANCELLED));
return CheckStatus(onFailure(ACTION_CANCELLED, result_));
}
else
{
Expand Down