moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
38 #include <rclcpp/logger.hpp>
39 #include <rclcpp/logging.hpp>
40 #include <moveit/utils/logger.hpp>
41 
42 namespace moveit
43 {
44 namespace tools
45 {
47 {
48  // spin a thread that will process user events
49  run_processing_thread_ = true;
50  processing_ = false;
51  processing_thread_ = std::make_unique<std::thread>([this]() { return processingThread(); });
52 }
53 
55 {
56  run_processing_thread_ = false;
57  new_action_condition_.notify_all();
58  processing_thread_->join();
59 }
60 
61 void BackgroundProcessing::processingThread()
62 {
63  std::unique_lock<std::mutex> ulock(action_lock_);
64 
65  while (run_processing_thread_)
66  {
67  while (actions_.empty() && run_processing_thread_)
68  new_action_condition_.wait(ulock);
69 
70  while (!actions_.empty())
71  {
72  JobCallback fn = actions_.front();
73  std::string action_name = action_names_.front();
74  actions_.pop_front();
75  action_names_.pop_front();
76  processing_ = true;
77 
78  // make sure we are unlocked while we process the event
79  action_lock_.unlock();
80  try
81  {
82  RCLCPP_DEBUG(moveit::getLogger("BackgroundProcessing"), "Begin executing '%s'", action_name.c_str());
83  fn();
84  RCLCPP_DEBUG(moveit::getLogger("BackgroundProcessing"), "Done executing '%s'", action_name.c_str());
85  }
86  catch (std::exception& ex)
87  {
88  RCLCPP_ERROR(moveit::getLogger("BackgroundProcessing"), "Exception caught while processing action '%s': %s",
89  action_name.c_str(), ex.what());
90  }
91  processing_ = false;
92  if (queue_change_event_)
93  queue_change_event_(COMPLETE, action_name);
94  action_lock_.lock();
95  }
96  }
97 }
98 
99 void BackgroundProcessing::addJob(const std::function<void()>& job, const std::string& name)
100 {
101  {
102  std::scoped_lock _(action_lock_);
103  actions_.push_back(job);
104  action_names_.push_back(name);
105  new_action_condition_.notify_all();
106  }
107  if (queue_change_event_)
108  queue_change_event_(ADD, name);
109 }
110 
112 {
113  bool update = false;
114  std::deque<std::string> removed;
115  {
116  std::scoped_lock _(action_lock_);
117  update = !actions_.empty();
118  actions_.clear();
119  action_names_.swap(removed);
120  }
121  if (update && queue_change_event_)
122  {
123  for (const std::string& it : removed)
124  queue_change_event_(REMOVE, it);
125  }
126 }
127 
129 {
130  std::scoped_lock _(action_lock_);
131  return actions_.size() + (processing_ ? 1 : 0);
132 }
133 
135 {
136  std::scoped_lock _(action_lock_);
137  queue_change_event_ = event;
138 }
139 
141 {
143 }
144 
145 } // end of namespace tools
146 } // end of namespace moveit
~BackgroundProcessing()
Finishes currently executing job, clears the remaining queue.
void clear()
Clear the queue of jobs.
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.
void update(moveit::core::RobotState *self, bool force, std::string &category)
Definition: robot_state.cpp:47
Main namespace for MoveIt.
Definition: exceptions.h:43
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
name
Definition: setup.py:7