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

Only allow one spin_until_future_complete at a time #804

Merged
merged 1 commit into from
Jun 5, 2019
Merged
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: 15 additions & 3 deletions nav2_tasks/include/nav2_tasks/bt_action_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define NAV2_TASKS__BT_ACTION_NODE_HPP_

#include <memory>
#include <mutex>
#include <string>

#include "behaviortree_cpp/action_node.h"
Expand Down Expand Up @@ -51,7 +52,7 @@ class BtActionNode : public BT::AsyncActionNode
// but override on_init instead.
void onInit() final
{
node_ = nav2_util::generate_internal_node();
node_ = nav2_util::generate_internal_node(action_name_);

// Initialize the input and output messages
goal_ = typename ActionT::Goal();
Expand Down Expand Up @@ -123,7 +124,12 @@ class BtActionNode : public BT::AsyncActionNode
auto future_result = goal_handle_->async_result();
rclcpp::executor::FutureReturnCode rc;
do {
rc = rclcpp::spin_until_future_complete(node_, future_result, node_loop_timeout_);
{
// Can only have one spin_until_future_complete at a time. Otherwise we get
// the "already on a executor" error
std::lock_guard<std::mutex> guard(spin_mutex_);
rc = rclcpp::spin_until_future_complete(node_, future_result, node_loop_timeout_);
}

if (rc == rclcpp::executor::FutureReturnCode::TIMEOUT) {
on_loop_timeout();
Expand Down Expand Up @@ -165,7 +171,10 @@ class BtActionNode : public BT::AsyncActionNode
if (status() == BT::NodeStatus::RUNNING) {
action_client_->async_cancel_goal(goal_handle_);
auto future_cancel = action_client_->async_cancel_goal(goal_handle_);
rclcpp::spin_until_future_complete(node_, future_cancel);
{
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Semantics, but this is right before leaving the scope of the if, so the additional scoping for the lock isn't required

std::lock_guard<std::mutex> guard(spin_mutex_);
rclcpp::spin_until_future_complete(node_, future_cancel);
}
}

setStatus(BT::NodeStatus::IDLE);
Expand All @@ -187,6 +196,9 @@ class BtActionNode : public BT::AsyncActionNode
// The timeout value while to use in the tick loop while waiting for
// a result from the server
std::chrono::milliseconds node_loop_timeout_;

// A mutex to allow only one spin_until_future_complete at a time
std::mutex spin_mutex_;
};

} // namespace nav2_tasks
Expand Down