38#include <rclcpp/logger.hpp>
39#include <rclcpp/logging.hpp>
49 run_processing_thread_ =
true;
51 processing_thread_ = std::make_unique<std::thread>([
this]() {
return processingThread(); });
56 run_processing_thread_ =
false;
57 new_action_condition_.notify_all();
58 processing_thread_->join();
61void BackgroundProcessing::processingThread()
63 std::unique_lock<std::mutex> ulock(action_lock_);
65 while (run_processing_thread_)
67 while (actions_.empty() && run_processing_thread_)
68 new_action_condition_.wait(ulock);
70 while (!actions_.empty())
73 std::string action_name = action_names_.front();
75 action_names_.pop_front();
79 action_lock_.unlock();
82 RCLCPP_DEBUG(
moveit::getLogger(
"moveit.ros.background_processing"),
"Begin executing '%s'", action_name.c_str());
84 RCLCPP_DEBUG(
moveit::getLogger(
"moveit.ros.background_processing"),
"Done executing '%s'", action_name.c_str());
86 catch (std::exception& ex)
89 "Exception caught while processing action '%s': %s", action_name.c_str(), ex.what());
92 if (queue_change_event_)
93 queue_change_event_(
COMPLETE, action_name);
102 std::scoped_lock _(action_lock_);
103 actions_.push_back(job);
104 action_names_.push_back(name);
105 new_action_condition_.notify_all();
107 if (queue_change_event_)
108 queue_change_event_(
ADD, name);
114 std::deque<std::string> removed;
116 std::scoped_lock _(action_lock_);
117 update = !actions_.empty();
119 action_names_.swap(removed);
121 if (update && queue_change_event_)
123 for (
const std::string& it : removed)
124 queue_change_event_(
REMOVE, it);
130 std::scoped_lock _(action_lock_);
131 return actions_.size() + (processing_ ? 1 : 0);
136 std::scoped_lock _(action_lock_);
137 queue_change_event_ = event;
Main namespace for MoveIt.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.