moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
background_processing.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan */
36
37#include <mutex>
38
40#include <rclcpp/logger.hpp>
41#include <rclcpp/logging.hpp>
43
44namespace moveit
45{
46namespace tools
47{
49{
50 // spin a thread that will process user events
51 run_processing_thread_ = true;
52 processing_ = false;
53 processing_thread_ = std::make_unique<std::thread>([this]() { return processingThread(); });
54}
55
57{
58 run_processing_thread_ = false;
59 new_action_condition_.notify_all();
60 processing_thread_->join();
61}
62
63void BackgroundProcessing::processingThread()
64{
65 std::unique_lock<std::mutex> ulock(action_lock_);
66
67 while (run_processing_thread_)
68 {
69 while (actions_.empty() && run_processing_thread_)
70 new_action_condition_.wait(ulock);
71
72 while (!actions_.empty())
73 {
74 JobCallback fn = actions_.front();
75 std::string action_name = action_names_.front();
76 actions_.pop_front();
77 action_names_.pop_front();
78 processing_ = true;
79
80 // make sure we are unlocked while we process the event
81 action_lock_.unlock();
82 try
83 {
84 RCLCPP_DEBUG(moveit::getLogger("moveit.ros.background_processing"), "Begin executing '%s'", action_name.c_str());
85 fn();
86 RCLCPP_DEBUG(moveit::getLogger("moveit.ros.background_processing"), "Done executing '%s'", action_name.c_str());
87 }
88 catch (std::exception& ex)
89 {
90 RCLCPP_ERROR(moveit::getLogger("moveit.ros.background_processing"),
91 "Exception caught while processing action '%s': %s", action_name.c_str(), ex.what());
92 }
93 processing_ = false;
94 if (queue_change_event_)
95 queue_change_event_(COMPLETE, action_name);
96 action_lock_.lock();
97 }
98 }
99}
100
101void BackgroundProcessing::addJob(const std::function<void()>& job, const std::string& name)
102{
103 {
104 std::scoped_lock _(action_lock_);
105 actions_.push_back(job);
106 action_names_.push_back(name);
107 new_action_condition_.notify_all();
108 }
109 if (queue_change_event_)
110 queue_change_event_(ADD, name);
111}
112
114{
115 bool update = false;
116 std::deque<std::string> removed;
117 {
118 std::scoped_lock _(action_lock_);
119 update = !actions_.empty();
120 actions_.clear();
121 action_names_.swap(removed);
122 }
123 if (update && queue_change_event_)
124 {
125 for (const std::string& it : removed)
126 queue_change_event_(REMOVE, it);
127 }
128}
129
131{
132 std::scoped_lock _(action_lock_);
133 return actions_.size() + (processing_ ? 1 : 0);
134}
135
137{
138 std::scoped_lock _(action_lock_);
139 queue_change_event_ = event;
140}
141
146
147} // end of namespace tools
148} // end of namespace moveit
~BackgroundProcessing()
Finishes currently executing job, clears the remaining queue.
void clearJobUpdateEvent()
Clear the callback to be triggered when events in JobEvent take place.
std::function< void(JobEvent, const std::string &)> JobUpdateCallback
The signature for callback triggered when job events take place: the event that took place and the na...
void setJobUpdateEvent(const JobUpdateCallback &event)
Set the callback to be triggered when events in JobEvent take place.
std::size_t getJobCount() const
Get the size of the queue of jobs (includes currently processed job).
@ REMOVE
Called when a job is removed from the queue without execution.
@ ADD
Called when a job is added to the queue.
@ COMPLETE
Called when a job is completed (and removed from the queue)
BackgroundProcessing()
Constructor. The background thread is activated automatically.
std::function< void()> JobCallback
The signature for job callbacks.
void addJob(const JobCallback &job, const std::string &name)
Add a job to the queue of jobs to execute. A name is also specifies for the job.
Main namespace for MoveIt.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79