background_processing.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/background_processing/background_processing.h>
00038 #include <console_bridge/console.h>
00039 
00040 moveit::tools::BackgroundProcessing::BackgroundProcessing()
00041 {
00042   // spin a thread that will process user events
00043   run_processing_thread_ = true;
00044   processing_ = false;
00045   processing_thread_.reset(new boost::thread(boost::bind(&BackgroundProcessing::processingThread, this)));
00046 }
00047 
00048 moveit::tools::BackgroundProcessing::~BackgroundProcessing()
00049 {
00050   run_processing_thread_ = false;
00051   new_action_condition_.notify_all();
00052   processing_thread_->join();
00053 }
00054 
00055 void moveit::tools::BackgroundProcessing::processingThread()
00056 {
00057   boost::unique_lock<boost::mutex> ulock(action_lock_);
00058 
00059   while (run_processing_thread_)
00060   {
00061     while (actions_.empty() && run_processing_thread_)
00062       new_action_condition_.wait(ulock);
00063 
00064     while (!actions_.empty())
00065     {
00066       JobCallback fn = actions_.front();
00067       std::string action_name = action_names_.front();
00068       actions_.pop_front();
00069       action_names_.pop_front();
00070       processing_ = true;
00071 
00072       // make sure we are unlocked while we process the event
00073       action_lock_.unlock();
00074       try
00075       {
00076         logDebug("moveit.background: Begin executing '%s'", action_name.c_str());
00077         fn();
00078         logDebug("moveit.background: Done executing '%s'", action_name.c_str());
00079       }
00080       catch(std::runtime_error &ex)
00081       {
00082         logError("Exception caught while processing action '%s': %s", action_name.c_str(), ex.what());
00083       }
00084       catch(...)
00085       {
00086         logError("Exception caught while processing action '%s'", action_name.c_str());
00087       }
00088       processing_ = false;
00089       if (queue_change_event_)
00090         queue_change_event_(COMPLETE, action_name);
00091       action_lock_.lock();
00092     }
00093   }
00094 }
00095 
00096 void moveit::tools::BackgroundProcessing::addJob(const boost::function<void()> &job, const std::string &name)
00097 {
00098   {
00099     boost::mutex::scoped_lock _(action_lock_);
00100     actions_.push_back(job);
00101     action_names_.push_back(name);
00102     new_action_condition_.notify_all();
00103   }
00104   if (queue_change_event_)
00105     queue_change_event_(ADD, name);
00106 }
00107 
00108 void moveit::tools::BackgroundProcessing::clear()
00109 {
00110   bool update = false;
00111   std::deque<std::string> removed;
00112   {
00113     boost::mutex::scoped_lock _(action_lock_);
00114     update = !actions_.empty();
00115     actions_.clear();
00116     action_names_.swap(removed);
00117   }
00118   if (update && queue_change_event_)
00119     for (std::deque<std::string>::iterator it = removed.begin() ; it != removed.end() ; ++it)
00120       queue_change_event_(REMOVE, *it);
00121 }
00122 
00123 std::size_t moveit::tools::BackgroundProcessing::getJobCount() const
00124 {
00125   boost::mutex::scoped_lock _(action_lock_);
00126   return actions_.size() + (processing_ ? 1 : 0);
00127 }
00128 
00129 void moveit::tools::BackgroundProcessing::setJobUpdateEvent(const JobUpdateCallback &event)
00130 {
00131   boost::mutex::scoped_lock _(action_lock_);
00132   queue_change_event_ = event;
00133 }
00134 
00135 void moveit::tools::BackgroundProcessing::clearJobUpdateEvent()
00136 {
00137   setJobUpdateEvent(JobUpdateCallback());
00138 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Aug 27 2015 13:58:52