histogram_visualizer.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 
00039 #include <pcl/common/common_headers.h>
00040 #include <pcl/visualization/common/common.h>
00041 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00042 #include <pcl/visualization/interactor.h>
00043 #else
00044 #include <vtkRenderWindowInteractor.h>
00045 #endif
00046 #include <pcl/visualization/histogram_visualizer.h>
00047 #include <pcl/visualization/boost.h>
00048 
00049 #include <vtkXYPlotActor.h>
00050 #include <vtkDoubleArray.h>
00051 #include <vtkTextProperty.h>
00052 #include <vtkRenderWindow.h>
00053 #include <vtkRenderer.h>
00054 #include <vtkDataObject.h>
00055 #include <vtkProperty2D.h>
00056 #include <vtkFieldData.h>
00057 
00059 pcl::visualization::PCLHistogramVisualizer::PCLHistogramVisualizer () : 
00060   wins_ (),
00061   exit_main_loop_timer_callback_ (vtkSmartPointer<ExitMainLoopTimerCallback>::New ()), 
00062   exit_callback_ (vtkSmartPointer<ExitCallback>::New ()), 
00063   stopped_ ()
00064 {
00065 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00066   resetStoppedFlag ();
00067 #endif
00068 }
00069 
00071 
00072 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00073 
00074 
00075 void
00076 pcl::visualization::PCLHistogramVisualizer::spinOnce (int time, bool force_redraw)
00077 {
00078   resetStoppedFlag ();
00079 
00080   if (time <= 0)
00081     time = 1;
00082   
00083   if (force_redraw)
00084   {
00085     for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00086     {
00087       (*am_it).second.interactor_->Render ();
00088       exit_main_loop_timer_callback_->right_timer_id = (*am_it).second.interactor_->CreateRepeatingTimer (time);
00089 
00090       exit_main_loop_timer_callback_->interact = (*am_it).second.interactor_;
00091 
00092       (*am_it).second.interactor_->Start ();
00093       (*am_it).second.interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id);
00094     }
00095     return;
00096   }
00097   
00098   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00099   {
00100     DO_EVERY(1.0/(*am_it).second.interactor_->GetDesiredUpdateRate (),
00101       (*am_it).second.interactor_->Render ();
00102       exit_main_loop_timer_callback_->right_timer_id = (*am_it).second.interactor_->CreateRepeatingTimer (time);
00103 
00104       exit_main_loop_timer_callback_->interact = (*am_it).second.interactor_;
00105 
00106       (*am_it).second.interactor_->Start ();
00107       (*am_it).second.interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id);
00108     );
00109   }
00110 }
00111 #else
00112 void
00113 pcl::visualization::PCLHistogramVisualizer::spinOnce (int time)
00114 {
00115   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00116   {
00117     DO_EVERY(1.0/(*am_it).second.interactor_->GetDesiredUpdateRate (),
00118       (*am_it).second.interactor_->Render ();
00119       exit_main_loop_timer_callback_->right_timer_id = (*am_it).second.interactor_->CreateRepeatingTimer (time);
00120 
00121       // Set the correct interactor for callbacks
00122       exit_main_loop_timer_callback_->interact = (*am_it).second.interactor_;
00123       (*am_it).second.interactor_->Start ();
00124       (*am_it).second.interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id);
00125     );
00126   }
00127 }
00128 #endif
00129 
00130 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00131 
00132 void
00133 pcl::visualization::PCLHistogramVisualizer::spin ()
00134 {
00135   resetStoppedFlag ();
00136   do
00137   {
00138     spinOnce ();
00139     for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00140     {
00141       if ((*am_it).second.interactor_->stopped)
00142         return;
00143     }
00144     boost::this_thread::sleep (boost::posix_time::seconds (1));
00145   }
00146   while (true);
00147 }
00149 bool 
00150 pcl::visualization::PCLHistogramVisualizer::wasStopped ()
00151 {
00152   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00153   {
00154     // If any of the interactors was stopped, return true (stop everything else)
00155     if ((*am_it).second.interactor_->stopped)
00156       return (true);
00157   }
00158   return (false);
00159 }
00160 
00162 void 
00163 pcl::visualization::PCLHistogramVisualizer::resetStoppedFlag () 
00164 { 
00165   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00166     (*am_it).second.interactor_->stopped = false; 
00167 }
00168 
00169 #else
00170 
00171 void
00172 pcl::visualization::PCLHistogramVisualizer::spin ()
00173 {
00174   stopped_ = false;
00175   do
00176   {
00177     spinOnce ();
00178     if (stopped_)
00179       break;
00180     boost::this_thread::sleep (boost::posix_time::seconds (1));
00181   }
00182   while (true);
00183 }
00184 #endif
00185 
00187 void 
00188 pcl::visualization::PCLHistogramVisualizer::setBackgroundColor (const double &r, const double &g, const double &b)
00189 {
00190   /*
00191   rens_->InitTraversal ();
00192   vtkRenderer* renderer = NULL;
00193   int i = 1;
00194   while ((renderer = rens_->GetNextItem ()) != NULL)
00195   {
00196     // Should we add the actor to all renderers?
00197     if (viewport == 0)
00198     {
00199       renderer->SetBackground (r, g, b);
00200       renderer->Render ();
00201     }
00202     else if (viewport == i)               // add the actor only to the specified viewport
00203     {
00204       renderer->SetBackground (r, g, b);
00205       renderer->Render ();
00206     }
00207     ++i;
00208   }
00209   */
00210   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00211   {
00212     (*am_it).second.ren_->SetBackground (r, g, b);
00213     (*am_it).second.ren_->Render ();
00214   }
00215 }
00216 
00218 void 
00219 pcl::visualization::PCLHistogramVisualizer::setGlobalYRange (float minp, float maxp)
00220 {
00221   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00222   {
00223     (*am_it).second.xy_plot_->SetYRange (minp, maxp);
00224     (*am_it).second.xy_plot_->Modified ();
00225   }
00226 }
00227 
00229 void 
00230 pcl::visualization::PCLHistogramVisualizer::updateWindowPositions ()
00231 {
00232   int posx = 0, posy = 0;
00233   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00234   {
00235     // Get the screen size
00236     int *scr_size = (*am_it).second.win_->GetScreenSize ();
00237     int *win_size = (*am_it).second.win_->GetActualSize ();
00238 
00239     // Update the position of the current window
00240     (*am_it).second.win_->SetPosition (posx, posy);
00241     (*am_it).second.win_->Modified ();
00242     // If there is space on Y, go on Y first
00243     if ((posy + win_size[1]) <= scr_size[1]) 
00244       posy += win_size[1];
00245     // Go on X
00246     else
00247     {
00248       posy = 0;
00249       if ((posx + win_size[0]) <= scr_size[0]) 
00250         posx += win_size[0];
00251       else
00252         posx = 0;
00253     }
00254   }
00255 }
00256 
00258 void 
00259 pcl::visualization::PCLHistogramVisualizer::reCreateActor (
00260     const vtkSmartPointer<vtkDoubleArray> &xy_array, RenWinInteract* renwinupd, const int hsize)
00261 {
00262   renwinupd->ren_->RemoveActor2D (renwinupd->xy_plot_);
00263   renwinupd->xy_plot_->RemoveAllInputs ();
00264   
00265   double min_max[2];
00266   xy_array->GetRange (min_max, 1);
00267 
00268   // Create the data structures
00269   vtkSmartPointer<vtkFieldData> field_values = vtkSmartPointer<vtkFieldData>::New ();
00270   field_values->AddArray (xy_array);
00271 
00272   vtkSmartPointer<vtkDataObject> field_data = vtkSmartPointer<vtkDataObject>::New ();
00273   field_data->SetFieldData (field_values);
00274 
00275   renwinupd->xy_plot_->AddDataObjectInput (field_data);
00276   renwinupd->ren_->AddActor2D (renwinupd->xy_plot_);
00277   
00278   renwinupd->xy_plot_->SetYTitle (""); renwinupd->xy_plot_->SetXTitle ("");
00279   renwinupd->xy_plot_->SetYRange (min_max[0], min_max[1]); 
00280   renwinupd->xy_plot_->SetXRange (0, hsize - 1);
00281 }
00282    
00283 
00285 void
00286 pcl::visualization::PCLHistogramVisualizer::createActor (
00287     const vtkSmartPointer<vtkDoubleArray> &xy_array, 
00288     pcl::visualization::RenWinInteract &renwinint,
00289     const std::string &id, const int win_width, const int win_height)
00290 {
00291   // Create the actor
00292   renwinint.xy_plot_->SetDataObjectPlotModeToColumns ();
00293   renwinint.xy_plot_->SetXValuesToValue ();
00294 
00295   // Create the data structures
00296   vtkSmartPointer<vtkFieldData> field_values = vtkSmartPointer<vtkFieldData>::New ();
00297   field_values->AddArray (xy_array);
00298 
00299   vtkSmartPointer<vtkDataObject> field_data = vtkSmartPointer<vtkDataObject>::New ();
00300   field_data->SetFieldData (field_values);
00301 
00302   renwinint.xy_plot_->AddDataObjectInput (field_data);
00303   // Set the plot color
00304   renwinint.xy_plot_->SetPlotColor (0, 1.0, 0.0, 0.0);
00305 
00306   renwinint.xy_plot_->SetDataObjectXComponent (0, 0); renwinint.xy_plot_->SetDataObjectYComponent (0, 1);
00307   renwinint.xy_plot_->PlotPointsOn ();
00308   //renwinint.xy_plot_->PlotCurvePointsOn ();
00309   //renwinint.xy_plot_->PlotLinesOn ();
00310   renwinint.xy_plot_->PlotCurveLinesOn ();
00311 
00312   // Get min-max range
00313   double min_max[2];
00314   xy_array->GetRange (min_max, 1);
00315 
00316   renwinint.xy_plot_->SetYTitle (""); renwinint.xy_plot_->SetXTitle ("");
00317   renwinint.xy_plot_->SetYRange (min_max[0], min_max[1]); 
00318   renwinint.xy_plot_->SetXRange (0, static_cast<double> (xy_array->GetNumberOfTuples () - 1));
00319 
00320   //renwinint.xy_plot_->SetTitle (id.c_str ());
00321   renwinint.xy_plot_->GetProperty ()->SetColor (0, 0, 0);
00322 
00323   // Adjust text properties
00324   vtkSmartPointer<vtkTextProperty> tprop = renwinint.xy_plot_->GetTitleTextProperty ();
00325   renwinint.xy_plot_->AdjustTitlePositionOn ();
00326   tprop->SetFontSize (8);
00327   tprop->ShadowOff (); tprop->ItalicOff ();
00328   tprop->SetColor (renwinint.xy_plot_->GetProperty ()->GetColor ());
00329 
00330   renwinint.xy_plot_->SetAxisLabelTextProperty (tprop);
00331   renwinint.xy_plot_->SetAxisTitleTextProperty (tprop);
00332   renwinint.xy_plot_->SetNumberOfXLabels (8);
00333   renwinint.xy_plot_->GetProperty ()->SetPointSize (3);
00334   renwinint.xy_plot_->GetProperty ()->SetLineWidth (2);
00335 
00336   renwinint.xy_plot_->SetPosition (0, 0);
00337   renwinint.xy_plot_->SetWidth (1); renwinint.xy_plot_->SetHeight (1);
00338 
00339   // Create the new window with its interactor and renderer
00340   renwinint.ren_->AddActor2D (renwinint.xy_plot_);
00341   renwinint.ren_->SetBackground (1, 1, 1);
00342   renwinint.win_->SetWindowName (id.c_str ());
00343   renwinint.win_->AddRenderer (renwinint.ren_);
00344   renwinint.win_->SetSize (win_width, win_height);
00345   renwinint.win_->SetBorders (1);
00346   
00347   // Create the interactor style
00348   vtkSmartPointer<pcl::visualization::PCLHistogramVisualizerInteractorStyle> style_ = vtkSmartPointer<pcl::visualization::PCLHistogramVisualizerInteractorStyle>::New ();
00349   style_->Initialize ();
00350   renwinint.style_ = style_;
00351   renwinint.style_->UseTimersOn ();
00352 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00353   renwinint.interactor_ = vtkSmartPointer<PCLVisualizerInteractor>::New ();
00354 #else
00355   renwinint.interactor_ = vtkSmartPointer<vtkRenderWindowInteractor>::New ();
00356 #endif
00357   renwinint.interactor_->SetRenderWindow (renwinint.win_);
00358   renwinint.interactor_->SetInteractorStyle (renwinint.style_);
00359   // Initialize and create timer
00360   renwinint.interactor_->Initialize ();
00361   renwinint.interactor_->CreateRepeatingTimer (5000L);
00362 
00363   exit_main_loop_timer_callback_->right_timer_id = -1;
00364   renwinint.interactor_->AddObserver (vtkCommand::TimerEvent, exit_main_loop_timer_callback_);
00365 #if !((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00366   exit_callback_->his = this;
00367 #endif
00368   renwinint.interactor_->AddObserver (vtkCommand::ExitEvent, exit_callback_);
00369 }
00370 
00372 bool
00373 pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram (
00374     const pcl::PCLPointCloud2 &cloud, const std::string &field_name,
00375     const std::string &id, int win_width, int win_height)
00376 {
00377   // Get the field
00378   int field_idx = pcl::getFieldIndex (cloud, field_name);
00379   if (field_idx == -1)
00380   {
00381     PCL_ERROR ("[addFeatureHistogram] Invalid field (%s) given!", field_name.c_str ());
00382     return (false);
00383   }
00384 
00385   RenWinInteractMap::iterator am_it = wins_.find (id);
00386   if (am_it != wins_.end ())
00387   {
00388     PCL_WARN ("[addFeatureHistogram] A window with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
00389     return (false);
00390   }
00391 
00392   vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00393   xy_array->SetNumberOfComponents (2);
00394   xy_array->SetNumberOfTuples (cloud.fields[field_idx].count);
00395 
00396   // Parse the cloud data and store it in the array
00397   double xy[2];
00398   for (unsigned int d = 0; d < cloud.fields[field_idx].count; ++d)
00399   {
00400     xy[0] = d;
00401     float data;
00402     // TODO: replace float with the real data type
00403     memcpy (&data, &cloud.data[cloud.fields[field_idx].offset + d * sizeof (float)], sizeof (float));
00404     xy[1] = data;
00405     xy_array->SetTuple (d, xy);
00406   }
00407   RenWinInteract renwinint;
00408   createActor (xy_array, renwinint, id, win_width, win_height);
00409 
00410   // Save the pointer/ID pair to the global window map
00411   wins_[id] = renwinint;
00412 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00413   resetStoppedFlag ();
00414 #endif
00415   return (true);
00416 }
00417 
00419 bool
00420 pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram (
00421     const pcl::PCLPointCloud2 &cloud,
00422     const std::string &field_name, 
00423     const int index,
00424     const std::string &id, int win_width, int win_height)
00425 {
00426   if (index < 0 || index >= static_cast<int> (cloud.width * cloud.height))
00427   {
00428     PCL_ERROR ("[addFeatureHistogram] Invalid point index (%d) given!\n", index);
00429     return (false);
00430   }
00431 
00432   // Get the field
00433   int field_idx = pcl::getFieldIndex (cloud, field_name);
00434   if (field_idx == -1)
00435   {
00436     PCL_ERROR ("[addFeatureHistogram] The specified field <%s> does not exist!\n", field_name.c_str ());
00437     return (false);
00438   }
00439 
00440   RenWinInteractMap::iterator am_it = wins_.find (id);
00441   if (am_it != wins_.end ())
00442   {
00443     PCL_ERROR ("[addFeatureHistogram] A window with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
00444     return (false);
00445   }
00446 
00447   vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00448   xy_array->SetNumberOfComponents (2);
00449   xy_array->SetNumberOfTuples (cloud.fields[field_idx].count);
00450 
00451   // Compute the total size of the fields
00452   unsigned int fsize = 0;
00453   for (size_t i = 0; i < cloud.fields.size (); ++i)
00454     fsize += cloud.fields[i].count * pcl::getFieldSize (cloud.fields[i].datatype);
00455 
00456   // Parse the cloud data and store it in the array
00457   double xy[2];
00458   for (unsigned int d = 0; d < cloud.fields[field_idx].count; ++d)
00459   {
00460     xy[0] = d;
00461     float data;
00462     // TODO: replace float with the real data type
00463     memcpy (&data, &cloud.data[index * fsize + cloud.fields[field_idx].offset + d * sizeof (float)], sizeof (float));
00464     xy[1] = data;
00465     xy_array->SetTuple (d, xy);
00466   }
00467   RenWinInteract renwinint;
00468   createActor (xy_array, renwinint, id, win_width, win_height);
00469 
00470   // Save the pointer/ID pair to the global window map
00471   wins_[id] = renwinint;
00472 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00473   resetStoppedFlag ();
00474 #endif
00475   return (true);
00476 }
00477 
00479 bool
00480 pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram (
00481     const pcl::PCLPointCloud2 &cloud, const std::string &field_name,
00482     const std::string &id)
00483 {
00484   RenWinInteractMap::iterator am_it = wins_.find (id);
00485   if (am_it == wins_.end ())
00486   {
00487     PCL_WARN ("[updateFeatureHistogram] A window with id <%s> does not exists!.\n", id.c_str ());
00488     return (false);
00489   }
00490   RenWinInteract* renwinupd = &wins_[id];
00491   vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00492   xy_array->SetNumberOfComponents (2);
00493 
00494   // Get the field
00495   int field_idx = pcl::getFieldIndex (cloud, field_name);
00496   if (field_idx == -1)
00497   {
00498     pcl::console::print_error ("[updateFeatureHistogram] Invalid field (%s) given!", field_name.c_str ());
00499     return (false);
00500   }
00501   xy_array->SetNumberOfTuples (cloud.fields[field_idx].count);
00502 
00503   // Parse the cloud data and store it in the array
00504   double xy[2];
00505   for (unsigned int d = 0; d < cloud.fields[field_idx].count; ++d)
00506   {
00507     xy[0] = d;
00508     float data;
00509     memcpy (&data, &cloud.data[cloud.fields[field_idx].offset + d * sizeof (float)], sizeof (float));
00510     xy[1] = data;
00511     xy_array->SetTuple (d, xy);
00512   }
00513   reCreateActor(xy_array, renwinupd, cloud.fields[field_idx].count - 1);
00514   return (true);
00515 }
00516 
00518 bool
00519 pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram (
00520     const pcl::PCLPointCloud2 &cloud,
00521     const std::string &field_name, 
00522     const int index,
00523     const std::string &id)
00524 {
00525   if (index < 0 || index >= static_cast<int> (cloud.width * cloud.height))
00526   {
00527     PCL_ERROR ("[updateFeatureHistogram] Invalid point index (%d) given!\n", index);
00528     return (false);
00529   }
00530   RenWinInteractMap::iterator am_it = wins_.find (id);
00531   if (am_it == wins_.end ())
00532   {
00533     PCL_WARN ("[updateFeatureHistogram] A window with id <%s> does not exists!.\n", id.c_str ());
00534     return (false);
00535   }
00536   RenWinInteract* renwinupd = &wins_[id];
00537   vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00538   xy_array->SetNumberOfComponents (2);
00539 
00540   // Get the field
00541   int field_idx = pcl::getFieldIndex (cloud, field_name);
00542   if (field_idx == -1)
00543   {
00544     pcl::console::print_error ("[updateFeatureHistogram] Invalid field (%s) given!", field_name.c_str ());
00545     return (false);
00546   }
00547   xy_array->SetNumberOfTuples (cloud.fields[field_idx].count);
00548   
00549   // Compute the total size of the fields
00550   unsigned int fsize = 0;
00551   for (size_t i = 0; i < cloud.fields.size (); ++i)
00552     fsize += cloud.fields[i].count * pcl::getFieldSize (cloud.fields[i].datatype);
00553 
00554   // Parse the cloud data and store it in the array
00555   double xy[2];
00556   for (unsigned int d = 0; d < cloud.fields[field_idx].count; ++d)
00557   {
00558     xy[0] = d;
00559     float data;
00560     memcpy (&data, &cloud.data[index * fsize + cloud.fields[field_idx].offset + d * sizeof (float)], sizeof (float));
00561     xy[1] = data;
00562     xy_array->SetTuple (d, xy);
00563   }
00564   reCreateActor(xy_array, renwinupd, cloud.fields[field_idx].count - 1);
00565   return (true);
00566 }
00567 
00569 void
00570 pcl::visualization::PCLHistogramVisualizer::ExitMainLoopTimerCallback::Execute (
00571     vtkObject*, unsigned long event_id, void* call_data)
00572 {
00573   if (event_id != vtkCommand::TimerEvent)
00574     return;
00575   int timer_id = *(reinterpret_cast<int*> (call_data));
00576 
00577   if (timer_id != right_timer_id)
00578     return;
00579 
00580   // Stop vtk loop and send notification to app to wake it up
00581 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00582   interact->stopLoop ();
00583 #else
00584   interact->TerminateApp ();
00585 #endif
00586 }
00587 
00589 void
00590 pcl::visualization::PCLHistogramVisualizer::ExitCallback::Execute (
00591     vtkObject*, unsigned long event_id, void*)
00592 {
00593   if (event_id != vtkCommand::ExitEvent)
00594     return;
00595   his->stopped_ = true;
00596 }
00597 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:43