40#include <rclcpp/logger.hpp>
41#include <rclcpp/logging.hpp>
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();
63void 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(
moveit::getLogger(
"moveit.ros.background_processing"),
"Begin executing '%s'", action_name.c_str());
86 RCLCPP_DEBUG(
moveit::getLogger(
"moveit.ros.background_processing"),
"Done executing '%s'", action_name.c_str());
88 catch (std::exception& ex)
91 "Exception caught while processing action '%s': %s", action_name.c_str(), ex.what());
94 if (queue_change_event_)
95 queue_change_event_(
COMPLETE, action_name);
104 std::scoped_lock _(action_lock_);
105 actions_.push_back(job);
106 action_names_.push_back(name);
107 new_action_condition_.notify_all();
109 if (queue_change_event_)
110 queue_change_event_(
ADD, name);
116 std::deque<std::string> removed;
118 std::scoped_lock _(action_lock_);
119 update = !actions_.empty();
121 action_names_.swap(removed);
123 if (update && queue_change_event_)
125 for (
const std::string& it : removed)
126 queue_change_event_(
REMOVE, it);
132 std::scoped_lock _(action_lock_);
133 return actions_.size() + (processing_ ? 1 : 0);
138 std::scoped_lock _(action_lock_);
139 queue_change_event_ = event;
Main namespace for MoveIt.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.