Skip to content

Commit

Permalink
refactor of #2624 for simplicity (#2629)
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveMacenski authored Oct 19, 2021
1 parent b3df8ca commit e1a5d54
Showing 1 changed file with 32 additions and 42 deletions.
74 changes: 32 additions & 42 deletions nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,11 +183,11 @@ class BtActionNode : public BT::ActionNodeBase
send_new_goal();
}

// if new goal was sent and action server has not yet responded
// check the future goal handle
if (future_goal_handle_) {
auto elapsed = (node_->now() - time_goal_sent_).to_chrono<std::chrono::milliseconds>();
try {
try {
// if new goal was sent and action server has not yet responded
// check the future goal handle
if (future_goal_handle_) {
auto elapsed = (node_->now() - time_goal_sent_).to_chrono<std::chrono::milliseconds>();
if (!is_future_goal_handle_complete(elapsed)) {
// return RUNNING if there is still some time before timeout happens
if (elapsed < server_timeout_) {
Expand All @@ -201,31 +201,20 @@ class BtActionNode : public BT::ActionNodeBase
future_goal_handle_.reset();
return BT::NodeStatus::FAILURE;
}
} catch (const std::runtime_error & e) {
if (e.what() == std::string("send_goal failed") ||
e.what() == std::string("Goal was rejected by the action server"))
{
return BT::NodeStatus::FAILURE;
} else {
// Internal exception to propogate to the tree
throw e;
}
}
}

// The following code corresponds to the "RUNNING" loop
if (rclcpp::ok() && !goal_result_available_) {
// user defined callback. May modify the value of "goal_updated_"
on_wait_for_result();
// The following code corresponds to the "RUNNING" loop
if (rclcpp::ok() && !goal_result_available_) {
// user defined callback. May modify the value of "goal_updated_"
on_wait_for_result();

auto goal_status = goal_handle_->get_status();
if (goal_updated_ && (goal_status == action_msgs::msg::GoalStatus::STATUS_EXECUTING ||
goal_status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED))
{
goal_updated_ = false;
send_new_goal();
auto elapsed = (node_->now() - time_goal_sent_).to_chrono<std::chrono::milliseconds>();
try {
auto goal_status = goal_handle_->get_status();
if (goal_updated_ && (goal_status == action_msgs::msg::GoalStatus::STATUS_EXECUTING ||
goal_status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED))
{
goal_updated_ = false;
send_new_goal();
auto elapsed = (node_->now() - time_goal_sent_).to_chrono<std::chrono::milliseconds>();
if (!is_future_goal_handle_complete(elapsed)) {
if (elapsed < server_timeout_) {
return BT::NodeStatus::RUNNING;
Expand All @@ -237,24 +226,25 @@ class BtActionNode : public BT::ActionNodeBase
future_goal_handle_.reset();
return BT::NodeStatus::FAILURE;
}
} catch (const std::runtime_error & e) {
if (e.what() == std::string("send_goal failed") ||
e.what() == std::string("Goal was rejected by the action server"))
{
return BT::NodeStatus::FAILURE;
} else {
// Internal exception to propogate to the tree
throw e;
}
}
}

callback_group_executor_.spin_some();
callback_group_executor_.spin_some();

// check if, after invoking spin_some(), we finally received the result
if (!goal_result_available_) {
// Yield this Action, returning RUNNING
return BT::NodeStatus::RUNNING;
// check if, after invoking spin_some(), we finally received the result
if (!goal_result_available_) {
// Yield this Action, returning RUNNING
return BT::NodeStatus::RUNNING;
}
}
} catch (const std::runtime_error & e) {
if (e.what() == std::string("send_goal failed") ||
e.what() == std::string("Goal was rejected by the action server"))
{
// Action related failure that should not fail the tree, but the node
return BT::NodeStatus::FAILURE;
} else {
// Internal exception to propogate to the tree
throw e;
}
}

Expand Down

0 comments on commit e1a5d54

Please sign in to comment.