Skip to content

Commit

Permalink
Reimplement the fix a concurrency problem in the multithreaded executor
Browse files Browse the repository at this point in the history
Reimplement the fix to correct a concurrency problem in the multithreaded executor.
This time, the AnyExecutable class has a boolean flag to reset / not reset the callback group `can_be_taken_from_` variable on destruction.
The multithreaded executor initializes the executor with that flag set to false.

Issue: #702
Signed-off-by: Guillaume Autran <gautran@clearpath.ai>
  • Loading branch information
guillaumeautran committed Apr 22, 2019
1 parent 97ed34a commit a4e6535
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 8 deletions.
5 changes: 4 additions & 1 deletion rclcpp/include/rclcpp/any_executable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ namespace executor
struct AnyExecutable
{
RCLCPP_PUBLIC
AnyExecutable();
AnyExecutable(bool auto_reset_group = true);

RCLCPP_PUBLIC
virtual ~AnyExecutable();
Expand All @@ -50,6 +50,9 @@ struct AnyExecutable
// These are used to keep the scope on the containing items
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group;
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base;

// Automatically reset the callback_group `can_be_taken_from` on destruction of this object
bool auto_reset_group;
};

} // namespace executor
Expand Down
7 changes: 4 additions & 3 deletions rclcpp/src/rclcpp/any_executable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,22 +16,23 @@

using rclcpp::executor::AnyExecutable;

AnyExecutable::AnyExecutable()
AnyExecutable::AnyExecutable(bool auto_reset_group)
: subscription(nullptr),
subscription_intra_process(nullptr),
timer(nullptr),
service(nullptr),
client(nullptr),
callback_group(nullptr),
node_base(nullptr)
node_base(nullptr),
auto_reset_group(auto_reset_group)
{}

AnyExecutable::~AnyExecutable()
{
// Make sure that discarded (taken but not executed) AnyExecutable's have
// their callback groups reset. This can happen when an executor is canceled
// between taking an AnyExecutable and executing it.
if (callback_group) {
if (auto_reset_group && callback_group) {
callback_group->can_be_taken_from().store(true);
}
}
5 changes: 1 addition & 4 deletions rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ void
MultiThreadedExecutor::run(size_t)
{
while (rclcpp::ok(this->context_) && spinning.load()) {
executor::AnyExecutable any_exec;
executor::AnyExecutable any_exec(false);
{
std::lock_guard<std::mutex> wait_lock(wait_mutex_);
if (!rclcpp::ok(this->context_) || !spinning.load()) {
Expand Down Expand Up @@ -101,8 +101,5 @@ MultiThreadedExecutor::run(size_t)
scheduled_timers_.erase(it);
}
}
// Clear the callback_group to prevent the AnyExecutable destructor from
// resetting the callback group `can_be_taken_from`
any_exec.callback_group.reset();
}
}

0 comments on commit a4e6535

Please sign in to comment.