$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, 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, Inc. 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 * $Id: histogram_visualizer.cpp 36905 2011-05-27 00:34:09Z michael.s.dixon $ 00035 * 00036 */ 00037 00038 #include <pcl/common/common_headers.h> 00039 #include <pcl_visualization/common/common.h> 00040 #include <pcl_visualization/interactor.h> 00041 #include <pcl_visualization/histogram_visualizer.h> 00042 00044 pcl_visualization::PCLHistogramVisualizer::PCLHistogramVisualizer () : exit_main_loop_timer_callback_ (vtkSmartPointer<ExitMainLoopTimerCallback>::New ()), exit_callback_ (vtkSmartPointer<ExitCallback>::New ()) 00045 { 00046 /* // Create a Renderer 00047 vtkSmartPointer<vtkRenderer> ren = vtkSmartPointer<vtkRenderer>::New (); 00048 // Add it to the list of renderers 00049 rens_->AddItem (ren); 00050 00051 // Create a RendererWindow 00052 win_ = vtkSmartPointer<vtkRenderWindow>::New (); 00053 win_->SetWindowName (name.c_str ()); 00054 00055 // Get screen size 00056 int *scr_size = win_->GetScreenSize (); 00057 // Set the window size as 1/2 of the screen size 00058 win_->SetSize (scr_size[0] / 2, scr_size[1] / 2); 00059 00060 // Add all renderers to the window 00061 rens_->InitTraversal (); 00062 vtkRenderer* renderer = NULL; 00063 while ((renderer = rens_->GetNextItem ()) != NULL) 00064 win_->AddRenderer (renderer); 00065 00066 // Create the interactor style 00067 style_->Initialize (); 00068 style_->setRendererCollection (rens_); 00069 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00070 style_->UseTimersOn (); 00071 00072 interactor_->SetInteractorStyle (style_); 00073 */ 00074 resetStoppedFlag (); 00075 } 00076 00078 00079 void 00080 pcl_visualization::PCLHistogramVisualizer::spinOnce (int time, bool force_redraw) 00081 { 00082 resetStoppedFlag (); 00083 00084 if (time <= 0) 00085 time = 1; 00086 00087 if (force_redraw) 00088 { 00089 for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it) 00090 { 00091 (*am_it).second.interactor_->Render (); 00092 exit_main_loop_timer_callback_->right_timer_id = (*am_it).second.interactor_->CreateRepeatingTimer (time); 00093 // Set the correct interactor to both callbacks 00094 exit_callback_->interact = (*am_it).second.interactor_; 00095 exit_main_loop_timer_callback_->interact = (*am_it).second.interactor_; 00096 00097 (*am_it).second.interactor_->Start (); 00098 (*am_it).second.interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id); 00099 } 00100 return; 00101 } 00102 00103 for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it) 00104 { 00105 DO_EVERY(1.0/(*am_it).second.interactor_->GetDesiredUpdateRate (), 00106 (*am_it).second.interactor_->Render (); 00107 exit_main_loop_timer_callback_->right_timer_id = (*am_it).second.interactor_->CreateRepeatingTimer (time); 00108 00109 // Set the correct interactor to both callbacks 00110 exit_callback_->interact = (*am_it).second.interactor_; 00111 exit_main_loop_timer_callback_->interact = (*am_it).second.interactor_; 00112 00113 (*am_it).second.interactor_->Start (); 00114 (*am_it).second.interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id); 00115 ); 00116 } 00117 } 00118 00120 void 00121 pcl_visualization::PCLHistogramVisualizer::spin () 00122 { 00123 resetStoppedFlag (); 00124 do 00125 { 00126 spinOnce (); 00127 for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it) 00128 { 00129 if ((*am_it).second.interactor_->stopped) 00130 return; 00131 } 00132 #ifdef _WIN32 00133 Sleep (1); 00134 #else 00135 usleep (1000); 00136 #endif 00137 } 00138 while (true); 00139 } 00140 00142 bool 00143 pcl_visualization::PCLHistogramVisualizer::wasStopped () 00144 { 00145 for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it) 00146 { 00147 // If any of the interactors was stopped, return true (stop everything else) 00148 if ((*am_it).second.interactor_->stopped) 00149 return (true); 00150 } 00151 return (false); 00152 } 00153 00155 void 00156 pcl_visualization::PCLHistogramVisualizer::resetStoppedFlag () 00157 { 00158 for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it) 00159 (*am_it).second.interactor_->stopped = false; 00160 } 00161 00163 void 00164 pcl_visualization::PCLHistogramVisualizer::setBackgroundColor (const double &r, const double &g, const double &b, int viewport) 00165 { 00166 /* rens_->InitTraversal (); 00167 vtkRenderer* renderer = NULL; 00168 int i = 1; 00169 while ((renderer = rens_->GetNextItem ()) != NULL) 00170 { 00171 // Should we add the actor to all renderers? 00172 if (viewport == 0) 00173 { 00174 renderer->SetBackground (r, g, b); 00175 renderer->Render (); 00176 } 00177 else if (viewport == i) // add the actor only to the specified viewport 00178 { 00179 renderer->SetBackground (r, g, b); 00180 renderer->Render (); 00181 } 00182 ++i; 00183 }*/ 00184 } 00185 00187 void 00188 pcl_visualization::PCLHistogramVisualizer::setGlobalYRange (float minp, float maxp) 00189 { 00190 for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it) 00191 { 00192 (*am_it).second.xy_plot_->SetYRange (minp, maxp); 00193 (*am_it).second.xy_plot_->Modified (); 00194 } 00195 } 00196 00198 void 00199 pcl_visualization::PCLHistogramVisualizer::updateWindowPositions () 00200 { 00201 int posx = 0, posy = 0; 00202 for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it) 00203 { 00204 // Get the screen size 00205 int *scr_size = (*am_it).second.win_->GetScreenSize (); 00206 int *win_size = (*am_it).second.win_->GetActualSize (); 00207 00208 // Update the position of the current window 00209 (*am_it).second.win_->SetPosition (posx, posy); 00210 (*am_it).second.win_->Modified (); 00211 // If there is space on Y, go on Y first 00212 if ((posy + win_size[1]) <= scr_size[1]) 00213 posy += win_size[1]; 00214 // Go on X 00215 else 00216 { 00217 posy = 0; 00218 if ((posx + win_size[0]) <= scr_size[0]) 00219 posx += win_size[0]; 00220 else 00221 posx = 0; 00222 } 00223 } 00224 } 00225 00227 bool 00228 pcl_visualization::PCLHistogramVisualizer::addFeatureHistogram ( 00229 const sensor_msgs::PointCloud2 &cloud, const std::string &field_name, 00230 const std::string &id, int win_width, int win_height) 00231 { 00232 RenWinInteractMap::iterator am_it = wins_.find (id); 00233 if (am_it != wins_.end ()) 00234 { 00235 pcl::console::print_error ("[addFeatureHistogram] A window with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); 00236 return (false); 00237 } 00238 00239 // Create the actor 00240 RenWinInteract renwinint; 00241 renwinint.xy_plot_->SetDataObjectPlotModeToColumns (); 00242 renwinint.xy_plot_->SetXValuesToValue (); 00243 00244 vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New (); 00245 xy_array->SetNumberOfComponents (2); 00246 00247 // Get the field 00248 int field_idx = pcl::getFieldIndex (cloud, field_name); 00249 if (field_idx == -1) 00250 { 00251 pcl::console::print_error ("[addFeatureHistogram] Invalid field (%s) given!", field_name.c_str ()); 00252 return (false); 00253 } 00254 xy_array->SetNumberOfTuples (cloud.fields[field_idx].count); 00255 00256 // Parse the cloud data and store it in the array 00257 double xy[2]; 00258 for (unsigned int d = 0; d < cloud.fields[field_idx].count; ++d) 00259 { 00260 xy[0] = d; 00261 float data; 00262 // TODO: replace float with the real data type 00263 memcpy (&data, &cloud.data[cloud.fields[field_idx].offset + d * sizeof (float)], sizeof (float)); 00264 xy[1] = data; 00265 xy_array->SetTuple (d, xy); 00266 } 00267 double min_max[2]; 00268 xy_array->GetRange (min_max, 1); 00269 00270 // Create the data structures 00271 vtkSmartPointer<vtkFieldData> field_values = vtkSmartPointer<vtkFieldData>::New (); 00272 field_values->AddArray (xy_array); 00273 00274 vtkSmartPointer<vtkDataObject> field_data = vtkSmartPointer<vtkDataObject>::New (); 00275 field_data->SetFieldData (field_values); 00276 00277 renwinint.xy_plot_->AddDataObjectInput (field_data); 00278 // Set the plot color 00279 renwinint.xy_plot_->SetPlotColor (0, 1.0, 0.0, 0.0); 00280 00281 renwinint.xy_plot_->SetDataObjectXComponent (0, 0); renwinint.xy_plot_->SetDataObjectYComponent (0, 1); 00282 renwinint.xy_plot_->PlotPointsOn (); 00283 //renwinint.xy_plot_->PlotCurvePointsOn (); 00284 //renwinint.xy_plot_->PlotLinesOn (); 00285 renwinint.xy_plot_->PlotCurveLinesOn (); 00286 00287 renwinint.xy_plot_->SetYTitle (""); renwinint.xy_plot_->SetXTitle (""); 00288 renwinint.xy_plot_->SetYRange (min_max[0], min_max[1]); 00289 renwinint.xy_plot_->SetXRange (0, cloud.fields[field_idx].count - 1); 00290 00291 //renwinint.xy_plot_->SetTitle (id.c_str ()); 00292 renwinint.xy_plot_->GetProperty ()->SetColor (0, 0, 0); 00293 00294 // Adjust text properties 00295 vtkSmartPointer<vtkTextProperty> tprop = renwinint.xy_plot_->GetTitleTextProperty (); 00296 renwinint.xy_plot_->AdjustTitlePositionOn (); 00297 tprop->SetFontSize (8); 00298 tprop->ShadowOff (); tprop->ItalicOff (); 00299 tprop->SetColor (renwinint.xy_plot_->GetProperty ()->GetColor ()); 00300 00301 renwinint.xy_plot_->SetAxisLabelTextProperty (tprop); 00302 renwinint.xy_plot_->SetAxisTitleTextProperty (tprop); 00303 renwinint.xy_plot_->SetNumberOfXLabels (8); 00304 renwinint.xy_plot_->GetProperty ()->SetPointSize (3); 00305 renwinint.xy_plot_->GetProperty ()->SetLineWidth (2); 00306 00307 renwinint.xy_plot_->SetPosition (0, 0); 00308 renwinint.xy_plot_->SetWidth (1); renwinint.xy_plot_->SetHeight (1); 00309 00310 // Create the new window with its interactor and renderer 00311 renwinint.ren_->AddActor2D (renwinint.xy_plot_); 00312 renwinint.ren_->SetBackground (1, 1, 1); 00313 renwinint.win_->SetWindowName (id.c_str ()); 00314 renwinint.win_->AddRenderer (renwinint.ren_); 00315 renwinint.win_->SetSize (win_width, win_height); 00316 renwinint.win_->SetBorders (1); 00317 00318 // Create the interactor style 00319 vtkSmartPointer<pcl_visualization::PCLHistogramVisualizerInteractorStyle> style_ = vtkSmartPointer<pcl_visualization::PCLHistogramVisualizerInteractorStyle>::New (); 00320 style_->Initialize (); 00321 renwinint.style_ = style_; 00322 renwinint.style_->UseTimersOn (); 00323 renwinint.interactor_ = vtkSmartPointer<PCLVisualizerInteractor>::New (); 00324 renwinint.interactor_->SetRenderWindow (renwinint.win_); 00325 renwinint.interactor_->SetInteractorStyle (renwinint.style_); 00326 // Initialize and create timer 00327 renwinint.interactor_->Initialize (); 00328 renwinint.interactor_->CreateRepeatingTimer (5000L); 00329 00330 exit_main_loop_timer_callback_->right_timer_id = -1; 00331 renwinint.interactor_->AddObserver (vtkCommand::TimerEvent, exit_main_loop_timer_callback_); 00332 00333 renwinint.interactor_->AddObserver (vtkCommand::ExitEvent, exit_callback_); 00334 00335 // Save the pointer/ID pair to the global window map 00336 wins_[id] = renwinint; 00337 00338 resetStoppedFlag (); 00339 return (true); 00340 } 00341 00342