$search
00001 /* 00002 * Copyright (c) 2011, 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 #include "object_segmentation_gui/object_segmenter.h" 00031 00032 #include "active_realtime_segmentation/pyra/tpimageutil.h" 00033 #include <sensor_msgs/image_encodings.h> 00034 #include "rviz_interaction_tools/image_tools.h" 00035 00036 00037 00038 namespace enc = sensor_msgs::image_encodings; 00039 00040 //Does not work right now, probably colliding with OGRE in Rviz 00041 //#define USE_CUDA 00042 00043 namespace object_segmentation_gui { 00044 00045 ObjectSegmenter::ObjectSegmenter( float grad_weight, int n_iter, 00046 bool use_gpu, float w_size, 00047 float b_size) 00048 : w_(640) 00049 , h_(480) 00050 , grad_weight_(grad_weight) 00051 , window_size_(w_size) 00052 , ball_size_(b_size) 00053 , use_gpu_(use_gpu) 00054 , n_iter_(n_iter) 00055 , init_(true) 00056 , num_fg_hypos_(0) 00057 , fgbgsegment(0) 00058 , gpu_image( w_, h_) 00059 , gpu_disparities( w_, h_) 00060 , init_mask( w_, h_) 00061 , segm_mask( w_, h_) 00062 , thread_(0) 00063 {} 00064 00065 ObjectSegmenter::~ObjectSegmenter() 00066 { 00067 if(thread_!=0){ 00068 stopThread(); 00069 thread_->join(); 00070 delete thread_; 00071 thread_=0; 00072 } 00073 00074 if(fgbgsegment!=0){ 00075 delete fgbgsegment; 00076 } 00077 00078 } 00079 00080 void ObjectSegmenter::setNewData( const sensor_msgs::Image &image, 00081 const stereo_msgs::DisparityImage &disparity) 00082 { 00083 stereo_msgs::DisparityImage local_disp = disparity; 00084 00085 // get the necessary parameters from the data 00086 w_ = image.width; 00087 h_ = image.height; 00088 drange_ = disparity.max_disparity - disparity.min_disparity; 00089 ROS_DEBUG("Image Width %d, Image Height %d", w_, h_); 00090 ROS_DEBUG("Disparity Range %d", drange_); 00091 ROS_DEBUG("Disparity steps %f", disparity.delta_d); 00092 ROS_DEBUG("Min and Max Disparity %f %f", 00093 disparity.min_disparity, disparity.max_disparity); 00094 00095 // make sure that invalid disparities are always below zero 00096 // and in the range between 0 and max_disparity-min_disparity 00097 // since that is the assumption made in the segmentation 00098 for(int x=0; x<w_; ++x){ 00099 for(int y=0; y<h_; ++y){ 00100 if(!rviz_interaction_tools::hasDisparityValue(disparity, y, x)){ 00101 float val; 00102 rviz_interaction_tools::getValue(disparity.image, y, x, val); 00103 val =- disparity.min_disparity; 00104 rviz_interaction_tools::setValue(local_disp.image, y, x, -1.0f); 00105 } 00106 } 00107 } 00108 00109 // memory align the RGB and disparity image 00110 gpu_image.SetDataAlign(image, 3*w_, h_, true); 00111 gpu_disparities.SetDataAlign(local_disp.image, w_, h_); 00112 00113 // gpu_disparities.Store("/wg/stor2a/jbohg/KinectDepth.ppm", true, false); 00114 00115 init_mask.SetSize(w_,h_); 00116 segm_mask.SetSize(w_,h_); 00117 00118 Fill(init_mask, (uchar)0); 00119 Fill(segm_mask, (uchar)0); 00120 // Create the segmentation object 00121 if(fgbgsegment!=0) 00122 delete fgbgsegment; 00123 fgbgsegment = new FgBgSegment(w_, h_, drange_, grad_weight_, 00124 window_size_, ball_size_); 00125 00126 #ifdef USE_CUDA 00127 fgbgsegment->UseGPU(use_gpu_); 00128 #else 00129 if(use_gpu_) 00130 ROS_WARN("CUDA support not enabled! Running segmentation on CPU."); 00131 fgbgsegment->UseGPU(false); 00132 00133 #endif //USE_CUDA 00134 00135 // After new data has been obtained, segmentation has to be initialised 00136 init_ = true; 00137 00138 startThread( boost::bind( &ObjectSegmenter::doSegment, this) ); 00139 } 00140 00141 void ObjectSegmenter::queueAction( const Action &action) 00142 { 00143 boost::mutex::scoped_lock lock(queue_mutex_); 00144 if(action.type_==STOP) 00145 action_queue_.clear(); 00146 action_queue_.push_back(action); 00147 cond_var_.notify_all(); 00148 00149 } 00150 00151 00152 bool ObjectSegmenter::dequeueAction( Action &action) 00153 { 00154 00155 boost::mutex::scoped_lock lock(queue_mutex_); 00156 00157 if(!action_queue_.empty()){ 00158 action = action_queue_[0]; 00159 action_queue_.pop_front(); 00160 return true; 00161 } else { 00162 return false; 00163 } 00164 00165 } 00166 00167 void ObjectSegmenter::clearQueue() 00168 { 00169 boost::mutex::scoped_lock lock(queue_mutex_); 00170 action_queue_.clear(); 00171 } 00172 00173 void ObjectSegmenter::waitForAction(){ 00174 00175 boost::mutex::scoped_lock q_lock(queue_mutex_); 00176 00177 while(init_ && action_queue_.empty()){ 00178 cond_var_.wait(q_lock); 00179 } 00180 } 00181 00182 void ObjectSegmenter::pause() 00183 { 00184 ROS_INFO("Entering pause"); 00185 boost::mutex::scoped_lock q_lock(queue_mutex_); 00186 ROS_INFO("Before pause condition variable waiting"); 00187 cond_var_.wait(q_lock); 00188 ROS_INFO("After pause condition variable waiting"); 00189 00190 } 00191 00192 bool ObjectSegmenter::getCurrentResult( sensor_msgs::Image &image) 00193 { 00194 00195 boost::mutex::scoped_lock lock(image_mutex_); 00196 fillImage(image, segm_mask); 00197 return true; 00198 00199 } 00200 00201 00202 void ObjectSegmenter::setCurrentResult( ) 00203 { 00204 boost::mutex::scoped_lock lock(image_mutex_); 00205 fgbgsegment->MakeSegmentImage(segm_mask); 00206 fgbgsegment->GetSurfaceParameters( alpha_, beta_, gamma_); 00207 } 00208 00209 bool ObjectSegmenter::validResult( const Image<uint8_t> &segm_mask) 00210 { 00211 boost::mutex::scoped_lock lock(image_mutex_); 00212 00213 int w = segm_mask.GetWidth(); 00214 int h = segm_mask.GetHeight(); 00215 00216 uint8_t *segm_d = segm_mask.GetData(); 00217 00218 std::vector<int> segm_size; 00219 segm_size.resize(num_fg_hypos_+1,0); 00220 00221 for(unsigned int i=0; i<w; ++i) 00222 for(unsigned int j=0; j<h; ++j){ 00223 int adr = j*w+i; 00224 int label = segm_d[adr]; 00225 if(label>1) 00226 segm_size[label-1]++; 00227 else if (label==1) 00228 segm_size[0]++; 00229 } 00230 00231 int sum = 0; 00232 for(int i=1; i<(int)segm_size.size(); ++i) 00233 sum += segm_size[i]; 00234 00235 if((int)segm_size.size()>1 && sum==0) 00236 return false; 00237 else 00238 return true; 00239 } 00240 00241 void ObjectSegmenter::getCurrentSurface(float &alpha, float &beta, 00242 float &gamma) 00243 { 00244 boost::mutex::scoped_lock lock(image_mutex_); 00245 alpha = alpha_; 00246 beta = beta_; 00247 gamma = gamma_; 00248 } 00249 00250 void ObjectSegmenter::getCurrentSegmFlags( bool &with_colors, 00251 bool &with_color_holes, 00252 bool &uniform, 00253 bool &with_disparities, 00254 bool &with_surface ) 00255 { 00256 with_colors = fgbgsegment->GetWithColors(); 00257 with_color_holes = fgbgsegment->GetWithColorHoles(); 00258 uniform = fgbgsegment->GetUniform(); 00259 with_disparities = fgbgsegment->GetWithDisparities(); 00260 with_surface = fgbgsegment->GetWithSurface(); 00261 } 00262 00263 void ObjectSegmenter::setCurrentSegmFlags( bool with_colors, 00264 bool with_color_holes, 00265 bool uniform, 00266 bool with_disparities, 00267 bool with_surface ) 00268 { 00269 fgbgsegment->SetWithColors(with_colors); 00270 fgbgsegment->SetWithColorHoles(with_color_holes); 00271 fgbgsegment->SetUniform(uniform); 00272 fgbgsegment->SetWithDisparities(with_disparities); 00273 fgbgsegment->SetWithSurface(with_surface); 00274 } 00275 00276 // execute by segmentation thread 00277 void ObjectSegmenter::doSegment() 00278 { 00279 00280 bool stop = false; 00281 00282 while(true){ 00283 00284 // while no seed points have been set, wait for control input 00285 waitForAction(); 00286 00287 fgbgsegment->Execute(gpu_image, gpu_disparities, init_, n_iter_); 00288 if(init_) 00289 init_ = false; 00290 00291 setCurrentResult(); 00292 00293 Action ac; 00294 if( dequeueAction(ac) ){ 00295 switch(ac.type_){ 00296 case REGION: 00297 fillInitMask(init_mask, ac.box_.p_tl_.x, ac.box_.p_tl_.y, 00298 ac.box_.p_br_.x, ac.box_.p_br_.y); 00299 fgbgsegment->SetNewForeground(init_mask, gpu_disparities, drange_); 00300 num_fg_hypos_++; 00301 break; 00302 case CLICK: 00303 if( !(ac.box_.p_tl_.x==-1 && ac.box_.p_tl_.y==-1)){ 00304 fgbgsegment->SetNewForeground( ac.box_.p_tl_.x, ac.box_.p_tl_.y, 00305 gpu_disparities, drange_); 00306 num_fg_hypos_++; 00307 } 00308 break; 00309 case RESET: 00310 setCurrentSegmFlags(ac.with_colors_, 00311 ac.with_color_holes_, 00312 ac.uniform_, 00313 ac.with_disparities_, 00314 ac.with_surface_); 00315 init_ = true; 00316 Fill(init_mask, (uchar)0); 00317 Fill(segm_mask, (uchar)0); 00318 break; 00319 case GRADCHANGE: 00320 fgbgsegment->SetGradWeight( ac.grad_weight_); 00321 break; 00322 case STOP: 00323 stop = true; 00324 clearQueue(); 00325 break; 00326 case PAUSE: 00327 pause(); 00328 break; 00329 } 00330 } 00331 00332 if(stop) 00333 break; 00334 } 00335 00336 } 00337 00338 template <typename Callable> 00339 void ObjectSegmenter::startThread( Callable f ) 00340 { 00341 if ( thread_ != 0) { 00342 thread_->join(); 00343 delete thread_; 00344 } 00345 thread_ = new boost::thread( f ); 00346 } 00347 00348 void ObjectSegmenter::stopThread(){ 00349 00350 ObjectSegmenter::Action action; 00351 action.type_ = ObjectSegmenter::STOP; 00352 queueAction(action); 00353 } 00354 00355 // produce mask image for segment initialisation 00356 void ObjectSegmenter::fillInitMask( Image<uint8_t> &init_mask, 00357 int start_x, int start_y, 00358 int stop_x, int stop_y){ 00359 00360 uint8_t *init_d = init_mask.GetData(); 00361 Fill(init_mask, (uchar)0); 00362 00363 if(start_x>stop_x) 00364 swap(start_x, stop_x); 00365 00366 if(start_y>stop_y) 00367 swap(start_y, stop_y); 00368 00369 for(int y=start_y; y<stop_y; ++y){ 00370 for(int x=start_x; x<stop_x; ++x){ 00371 int i = y*w_ + x; 00372 init_d[i] = 1; 00373 } 00374 } 00375 } 00376 00377 00378 void ObjectSegmenter::fillImage(sensor_msgs::Image &image, 00379 const Image<uint8_t> &segm_mask) 00380 { 00381 uint8_t *segm_d = segm_mask.GetData(); 00382 00383 image.header.frame_id = "narrow_stereo_optical_frame"; 00384 image.header.stamp = ros::Time::now(); 00385 image.height = segm_mask.GetHeight(); 00386 image.width = segm_mask.GetWidth(); 00387 image.encoding = enc::MONO8; 00388 image.is_bigendian = false; 00389 image.step = segm_mask.GetWidth(); 00390 size_t size = image.step * image.height; 00391 image.data.resize(size); 00392 00393 for(unsigned int x=0; x<image.width; ++x){ 00394 for(unsigned int y=0; y<image.height; ++y){ 00395 int i = y * image.width + x; 00396 image.data[i] = segm_d[i]; 00397 } 00398 } 00399 } 00400 00401 00402 } 00403