38 #include <rclcpp/logger.hpp>
39 #include <rclcpp/logging.hpp>
46 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_background_processing.background_processing");
51 run_processing_thread_ =
true;
53 processing_thread_ = std::make_unique<std::thread>([
this]() {
return processingThread(); });
58 run_processing_thread_ =
false;
59 new_action_condition_.notify_all();
60 processing_thread_->join();
63 void BackgroundProcessing::processingThread()
65 std::unique_lock<std::mutex> ulock(action_lock_);
67 while (run_processing_thread_)
69 while (actions_.empty() && run_processing_thread_)
70 new_action_condition_.wait(ulock);
72 while (!actions_.empty())
75 std::string action_name = action_names_.front();
77 action_names_.pop_front();
81 action_lock_.unlock();
84 RCLCPP_DEBUG(LOGGER,
"Begin executing '%s'", action_name.c_str());
86 RCLCPP_DEBUG(LOGGER,
"Done executing '%s'", action_name.c_str());
88 catch (std::exception& ex)
90 RCLCPP_ERROR(LOGGER,
"Exception caught while processing action '%s': %s", action_name.c_str(), ex.what());
93 if (queue_change_event_)
94 queue_change_event_(
COMPLETE, action_name);
103 std::scoped_lock _(action_lock_);
104 actions_.push_back(job);
105 action_names_.push_back(
name);
106 new_action_condition_.notify_all();
108 if (queue_change_event_)
109 queue_change_event_(
ADD,
name);
115 std::deque<std::string> removed;
117 std::scoped_lock _(action_lock_);
118 update = !actions_.empty();
120 action_names_.swap(removed);
122 if (update && queue_change_event_)
123 for (
const std::string& it : removed)
124 queue_change_event_(
REMOVE, it);
129 std::scoped_lock _(action_lock_);
130 return actions_.size() + (processing_ ? 1 : 0);
135 std::scoped_lock _(action_lock_);
136 queue_change_event_ = event;
Main namespace for MoveIt.
const rclcpp::Logger LOGGER