00001 /* 00002 * Copyright (C) 2009, Willow Garage, Inc. 00003 * 00004 * Redistribution and use in source and binary forms, with or without 00005 * modification, are permitted provided that the following conditions are met: 00006 * * Redistributions of source code must retain the above copyright notice, 00007 * this list of conditions and the following disclaimer. 00008 * * Redistributions in binary form must reproduce the above copyright 00009 * notice, this list of conditions and the following disclaimer in the 00010 * documentation and/or other materials provided with the distribution. 00011 * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its 00012 * contributors may be used to endorse or promote products derived from 00013 * this software without specific prior written permission. 00014 * 00015 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00016 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00017 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00018 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00019 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00020 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00021 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00022 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00023 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00024 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00025 * POSSIBILITY OF SUCH DAMAGE. 00026 */ 00027 00028 #include "ros/spinner.h" 00029 #include "ros/ros.h" 00030 #include "ros/callback_queue.h" 00031 00032 #include <boost/thread/thread.hpp> 00033 00034 namespace ros 00035 { 00036 00037 void SingleThreadedSpinner::spin(CallbackQueue* queue) 00038 { 00039 ros::WallDuration timeout(0.1f); 00040 00041 if (!queue) 00042 { 00043 queue = getGlobalCallbackQueue(); 00044 } 00045 00046 ros::NodeHandle n; 00047 while (n.ok()) 00048 { 00049 queue->callAvailable(timeout); 00050 } 00051 } 00052 00053 MultiThreadedSpinner::MultiThreadedSpinner(uint32_t thread_count) 00054 : thread_count_(thread_count) 00055 { 00056 } 00057 00058 void MultiThreadedSpinner::spin(CallbackQueue* queue) 00059 { 00060 AsyncSpinner s(thread_count_, queue); 00061 s.start(); 00062 00063 ros::waitForShutdown(); 00064 } 00065 00066 class AsyncSpinnerImpl 00067 { 00068 public: 00069 AsyncSpinnerImpl(uint32_t thread_count, CallbackQueue* queue); 00070 ~AsyncSpinnerImpl(); 00071 void start(); 00072 void stop(); 00073 00074 private: 00075 void threadFunc(); 00076 00077 boost::mutex mutex_; 00078 boost::thread_group threads_; 00079 00080 uint32_t thread_count_; 00081 CallbackQueue* callback_queue_; 00082 00083 volatile bool continue_; 00084 00085 ros::NodeHandle nh_; 00086 }; 00087 00088 AsyncSpinnerImpl::AsyncSpinnerImpl(uint32_t thread_count, CallbackQueue* queue) 00089 : thread_count_(thread_count) 00090 , callback_queue_(queue) 00091 , continue_(false) 00092 { 00093 if (thread_count == 0) 00094 { 00095 thread_count_ = boost::thread::hardware_concurrency(); 00096 00097 if (thread_count_ == 0) 00098 { 00099 thread_count_ = 1; 00100 } 00101 } 00102 00103 if (!queue) 00104 { 00105 callback_queue_ = getGlobalCallbackQueue(); 00106 } 00107 } 00108 00109 AsyncSpinnerImpl::~AsyncSpinnerImpl() 00110 { 00111 stop(); 00112 } 00113 00114 void AsyncSpinnerImpl::start() 00115 { 00116 boost::mutex::scoped_lock lock(mutex_); 00117 if (continue_) 00118 { 00119 return; 00120 } 00121 00122 continue_ = true; 00123 00124 for (uint32_t i = 0; i < thread_count_; ++i) 00125 { 00126 threads_.create_thread(boost::bind(&AsyncSpinnerImpl::threadFunc, this)); 00127 } 00128 } 00129 00130 void AsyncSpinnerImpl::stop() 00131 { 00132 boost::mutex::scoped_lock lock(mutex_); 00133 if (!continue_) 00134 { 00135 return; 00136 } 00137 00138 continue_ = false; 00139 threads_.join_all(); 00140 } 00141 00142 void AsyncSpinnerImpl::threadFunc() 00143 { 00144 disableAllSignalsInThisThread(); 00145 00146 CallbackQueue* queue = callback_queue_; 00147 bool use_call_available = thread_count_ == 1; 00148 WallDuration timeout(0.1); 00149 00150 while (continue_ && nh_.ok()) 00151 { 00152 if (use_call_available) 00153 { 00154 queue->callAvailable(timeout); 00155 } 00156 else 00157 { 00158 queue->callOne(timeout); 00159 } 00160 } 00161 } 00162 00163 AsyncSpinner::AsyncSpinner(uint32_t thread_count) 00164 : impl_(new AsyncSpinnerImpl(thread_count, 0)) 00165 { 00166 } 00167 00168 AsyncSpinner::AsyncSpinner(uint32_t thread_count, CallbackQueue* queue) 00169 : impl_(new AsyncSpinnerImpl(thread_count, queue)) 00170 { 00171 } 00172 00173 void AsyncSpinner::start() 00174 { 00175 impl_->start(); 00176 } 00177 00178 void AsyncSpinner::stop() 00179 { 00180 impl_->stop(); 00181 } 00182 00183 }