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


visualization
Author(s): Ioan Sucan , Dave Coleman
autogenerated on Mon Oct 6 2014 02:34:03