histogram_visualizer.cpp
Go to the documentation of this file.
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 6242 2012-07-08 22:41:55Z rusu $
00035  *
00036  */
00037 
00038 #include <boost/thread/thread.hpp>
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 
00049 pcl::visualization::PCLHistogramVisualizer::PCLHistogramVisualizer () : 
00050   wins_ (),
00051   exit_main_loop_timer_callback_ (vtkSmartPointer<ExitMainLoopTimerCallback>::New ()), 
00052   exit_callback_ (vtkSmartPointer<ExitCallback>::New ())
00053 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00054   , stopped_ ()
00055 #endif
00056 {
00057 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00058   resetStoppedFlag ();
00059 #endif
00060 }
00061 
00063 
00064 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00065 
00066 
00067 void
00068 pcl::visualization::PCLHistogramVisualizer::spinOnce (int time, bool force_redraw)
00069 {
00070   resetStoppedFlag ();
00071 
00072   if (time <= 0)
00073     time = 1;
00074   
00075   if (force_redraw)
00076   {
00077     for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00078     {
00079       (*am_it).second.interactor_->Render ();
00080       exit_main_loop_timer_callback_->right_timer_id = (*am_it).second.interactor_->CreateRepeatingTimer (time);
00081 
00082       exit_main_loop_timer_callback_->interact = (*am_it).second.interactor_;
00083 
00084       (*am_it).second.interactor_->Start ();
00085       (*am_it).second.interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id);
00086     }
00087     return;
00088   }
00089   
00090   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00091   {
00092     DO_EVERY(1.0/(*am_it).second.interactor_->GetDesiredUpdateRate (),
00093       (*am_it).second.interactor_->Render ();
00094       exit_main_loop_timer_callback_->right_timer_id = (*am_it).second.interactor_->CreateRepeatingTimer (time);
00095 
00096       exit_main_loop_timer_callback_->interact = (*am_it).second.interactor_;
00097 
00098       (*am_it).second.interactor_->Start ();
00099       (*am_it).second.interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id);
00100     );
00101   }
00102 }
00103 #else
00104 void
00105 pcl::visualization::PCLHistogramVisualizer::spinOnce (int time)
00106 {
00107   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00108   {
00109     DO_EVERY(1.0/(*am_it).second.interactor_->GetDesiredUpdateRate (),
00110       (*am_it).second.interactor_->Render ();
00111       exit_main_loop_timer_callback_->right_timer_id = (*am_it).second.interactor_->CreateRepeatingTimer (time);
00112 
00113       // Set the correct interactor for callbacks
00114       exit_main_loop_timer_callback_->interact = (*am_it).second.interactor_;
00115       (*am_it).second.interactor_->Start ();
00116       (*am_it).second.interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id);
00117     );
00118   }
00119 }
00120 #endif
00121 
00122 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00123 
00124 void
00125 pcl::visualization::PCLHistogramVisualizer::spin ()
00126 {
00127   resetStoppedFlag ();
00128   do
00129   {
00130     spinOnce ();
00131     for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00132     {
00133       if ((*am_it).second.interactor_->stopped)
00134         return;
00135     }
00136     boost::this_thread::sleep (boost::posix_time::seconds (1));
00137   }
00138   while (true);
00139 }
00141 bool 
00142 pcl::visualization::PCLHistogramVisualizer::wasStopped ()
00143 {
00144   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00145   {
00146     // If any of the interactors was stopped, return true (stop everything else)
00147     if ((*am_it).second.interactor_->stopped)
00148       return (true);
00149   }
00150   return (false);
00151 }
00152 
00154 void 
00155 pcl::visualization::PCLHistogramVisualizer::resetStoppedFlag () 
00156 { 
00157   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00158     (*am_it).second.interactor_->stopped = false; 
00159 }
00160 
00161 #else
00162 
00163 void
00164 pcl::visualization::PCLHistogramVisualizer::spin ()
00165 {
00166   stopped_ = false;
00167   do
00168   {
00169     spinOnce ();
00170     if (stopped_)
00171       break;
00172     boost::this_thread::sleep (boost::posix_time::seconds (1));
00173   }
00174   while (true);
00175 }
00176 #endif
00177 
00179 void 
00180 pcl::visualization::PCLHistogramVisualizer::setBackgroundColor (const double &, const double &, const double &, int)
00181 {
00182 /*  rens_->InitTraversal ();
00183   vtkRenderer* renderer = NULL;
00184   int i = 1;
00185   while ((renderer = rens_->GetNextItem ()) != NULL)
00186   {
00187     // Should we add the actor to all renderers?
00188     if (viewport == 0)
00189     {
00190       renderer->SetBackground (r, g, b);
00191       renderer->Render ();
00192     }
00193     else if (viewport == i)               // add the actor only to the specified viewport
00194     {
00195       renderer->SetBackground (r, g, b);
00196       renderer->Render ();
00197     }
00198     ++i;
00199   }*/
00200 }
00201 
00203 void 
00204 pcl::visualization::PCLHistogramVisualizer::setGlobalYRange (float minp, float maxp)
00205 {
00206   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00207   {
00208     (*am_it).second.xy_plot_->SetYRange (minp, maxp);
00209     (*am_it).second.xy_plot_->Modified ();
00210   }
00211 }
00212 
00214 void 
00215 pcl::visualization::PCLHistogramVisualizer::updateWindowPositions ()
00216 {
00217   int posx = 0, posy = 0;
00218   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00219   {
00220     // Get the screen size
00221     int *scr_size = (*am_it).second.win_->GetScreenSize ();
00222     int *win_size = (*am_it).second.win_->GetActualSize ();
00223 
00224     // Update the position of the current window
00225     (*am_it).second.win_->SetPosition (posx, posy);
00226     (*am_it).second.win_->Modified ();
00227     // If there is space on Y, go on Y first
00228     if ((posy + win_size[1]) <= scr_size[1]) 
00229       posy += win_size[1];
00230     // Go on X
00231     else
00232     {
00233       posy = 0;
00234       if ((posx + win_size[0]) <= scr_size[0]) 
00235         posx += win_size[0];
00236       else
00237         posx = 0;
00238     }
00239   }
00240 }
00241 
00243 void 
00244 pcl::visualization::PCLHistogramVisualizer::reCreateActor (
00245     const vtkSmartPointer<vtkDoubleArray> &xy_array, RenWinInteract* renwinupd, const int hsize)
00246 {
00247   renwinupd->ren_->RemoveActor2D (renwinupd->xy_plot_);
00248   renwinupd->xy_plot_->RemoveAllInputs ();
00249   
00250   double min_max[2];
00251   xy_array->GetRange (min_max, 1);
00252 
00253   // Create the data structures
00254   vtkSmartPointer<vtkFieldData> field_values = vtkSmartPointer<vtkFieldData>::New ();
00255   field_values->AddArray (xy_array);
00256 
00257   vtkSmartPointer<vtkDataObject> field_data = vtkSmartPointer<vtkDataObject>::New ();
00258   field_data->SetFieldData (field_values);
00259 
00260   renwinupd->xy_plot_->AddDataObjectInput (field_data);
00261   renwinupd->ren_->AddActor2D (renwinupd->xy_plot_);
00262   
00263   renwinupd->xy_plot_->SetYTitle (""); renwinupd->xy_plot_->SetXTitle ("");
00264   renwinupd->xy_plot_->SetYRange (min_max[0], min_max[1]); 
00265   renwinupd->xy_plot_->SetXRange (0, hsize - 1);
00266 }
00267    
00268 
00270 void
00271 pcl::visualization::PCLHistogramVisualizer::createActor (
00272     const vtkSmartPointer<vtkDoubleArray> &xy_array, 
00273     pcl::visualization::RenWinInteract &renwinint,
00274     const std::string &id, const int win_width, const int win_height)
00275 {
00276   // Create the actor
00277   renwinint.xy_plot_->SetDataObjectPlotModeToColumns ();
00278   renwinint.xy_plot_->SetXValuesToValue ();
00279 
00280   // Create the data structures
00281   vtkSmartPointer<vtkFieldData> field_values = vtkSmartPointer<vtkFieldData>::New ();
00282   field_values->AddArray (xy_array);
00283 
00284   vtkSmartPointer<vtkDataObject> field_data = vtkSmartPointer<vtkDataObject>::New ();
00285   field_data->SetFieldData (field_values);
00286 
00287   renwinint.xy_plot_->AddDataObjectInput (field_data);
00288   // Set the plot color
00289   renwinint.xy_plot_->SetPlotColor (0, 1.0, 0.0, 0.0);
00290 
00291   renwinint.xy_plot_->SetDataObjectXComponent (0, 0); renwinint.xy_plot_->SetDataObjectYComponent (0, 1);
00292   renwinint.xy_plot_->PlotPointsOn ();
00293   //renwinint.xy_plot_->PlotCurvePointsOn ();
00294   //renwinint.xy_plot_->PlotLinesOn ();
00295   renwinint.xy_plot_->PlotCurveLinesOn ();
00296 
00297   // Get min-max range
00298   double min_max[2];
00299   xy_array->GetRange (min_max, 1);
00300 
00301   renwinint.xy_plot_->SetYTitle (""); renwinint.xy_plot_->SetXTitle ("");
00302   renwinint.xy_plot_->SetYRange (min_max[0], min_max[1]); 
00303   renwinint.xy_plot_->SetXRange (0, static_cast<double> (xy_array->GetNumberOfTuples () - 1));
00304 
00305   //renwinint.xy_plot_->SetTitle (id.c_str ());
00306   renwinint.xy_plot_->GetProperty ()->SetColor (0, 0, 0);
00307 
00308   // Adjust text properties
00309   vtkSmartPointer<vtkTextProperty> tprop = renwinint.xy_plot_->GetTitleTextProperty ();
00310   renwinint.xy_plot_->AdjustTitlePositionOn ();
00311   tprop->SetFontSize (8);
00312   tprop->ShadowOff (); tprop->ItalicOff ();
00313   tprop->SetColor (renwinint.xy_plot_->GetProperty ()->GetColor ());
00314 
00315   renwinint.xy_plot_->SetAxisLabelTextProperty (tprop);
00316   renwinint.xy_plot_->SetAxisTitleTextProperty (tprop);
00317   renwinint.xy_plot_->SetNumberOfXLabels (8);
00318   renwinint.xy_plot_->GetProperty ()->SetPointSize (3);
00319   renwinint.xy_plot_->GetProperty ()->SetLineWidth (2);
00320 
00321   renwinint.xy_plot_->SetPosition (0, 0);
00322   renwinint.xy_plot_->SetWidth (1); renwinint.xy_plot_->SetHeight (1);
00323 
00324   // Create the new window with its interactor and renderer
00325   renwinint.ren_->AddActor2D (renwinint.xy_plot_);
00326   renwinint.ren_->SetBackground (1, 1, 1);
00327   renwinint.win_->SetWindowName (id.c_str ());
00328   renwinint.win_->AddRenderer (renwinint.ren_);
00329   renwinint.win_->SetSize (win_width, win_height);
00330   renwinint.win_->SetBorders (1);
00331   
00332   // Create the interactor style
00333   vtkSmartPointer<pcl::visualization::PCLHistogramVisualizerInteractorStyle> style_ = vtkSmartPointer<pcl::visualization::PCLHistogramVisualizerInteractorStyle>::New ();
00334   style_->Initialize ();
00335   renwinint.style_ = style_;
00336   renwinint.style_->UseTimersOn ();
00337 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00338   renwinint.interactor_ = vtkSmartPointer<PCLVisualizerInteractor>::New ();
00339 #else
00340   renwinint.interactor_ = vtkSmartPointer<vtkRenderWindowInteractor>::New ();
00341 #endif
00342   renwinint.interactor_->SetRenderWindow (renwinint.win_);
00343   renwinint.interactor_->SetInteractorStyle (renwinint.style_);
00344   // Initialize and create timer
00345   renwinint.interactor_->Initialize ();
00346   renwinint.interactor_->CreateRepeatingTimer (5000L);
00347 
00348   exit_main_loop_timer_callback_->right_timer_id = -1;
00349   renwinint.interactor_->AddObserver (vtkCommand::TimerEvent, exit_main_loop_timer_callback_);
00350 #if !((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00351   exit_callback_->his = this;
00352 #endif
00353   renwinint.interactor_->AddObserver (vtkCommand::ExitEvent, exit_callback_);
00354 }
00355 
00357 bool
00358 pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram (
00359     const sensor_msgs::PointCloud2 &cloud, const std::string &field_name, 
00360     const std::string &id, int win_width, int win_height)
00361 {
00362   // Get the field
00363   int field_idx = pcl::getFieldIndex (cloud, field_name);
00364   if (field_idx == -1)
00365   {
00366     PCL_ERROR ("[addFeatureHistogram] Invalid field (%s) given!", field_name.c_str ());
00367     return (false);
00368   }
00369 
00370   RenWinInteractMap::iterator am_it = wins_.find (id);
00371   if (am_it != wins_.end ())
00372   {
00373     PCL_WARN ("[addFeatureHistogram] A window with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
00374     return (false);
00375   }
00376 
00377   vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00378   xy_array->SetNumberOfComponents (2);
00379   xy_array->SetNumberOfTuples (cloud.fields[field_idx].count);
00380 
00381   // Parse the cloud data and store it in the array
00382   double xy[2];
00383   for (unsigned int d = 0; d < cloud.fields[field_idx].count; ++d)
00384   {
00385     xy[0] = d;
00386     float data;
00387     // TODO: replace float with the real data type
00388     memcpy (&data, &cloud.data[cloud.fields[field_idx].offset + d * sizeof (float)], sizeof (float));
00389     xy[1] = data;
00390     xy_array->SetTuple (d, xy);
00391   }
00392   RenWinInteract renwinint;
00393   createActor (xy_array, renwinint, id, win_width, win_height);
00394 
00395   // Save the pointer/ID pair to the global window map
00396   wins_[id] = renwinint;
00397 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00398   resetStoppedFlag ();
00399 #endif
00400   return (true);
00401 }
00402 
00404 bool
00405 pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram (
00406     const sensor_msgs::PointCloud2 &cloud, 
00407     const std::string &field_name, 
00408     const int index,
00409     const std::string &id, int win_width, int win_height)
00410 {
00411   if (index < 0 || index >= static_cast<int> (cloud.width * cloud.height))
00412   {
00413     PCL_ERROR ("[addFeatureHistogram] Invalid point index (%d) given!\n", index);
00414     return (false);
00415   }
00416 
00417   // Get the field
00418   int field_idx = pcl::getFieldIndex (cloud, field_name);
00419   if (field_idx == -1)
00420   {
00421     PCL_ERROR ("[addFeatureHistogram] The specified field <%s> does not exist!\n", field_name.c_str ());
00422     return (false);
00423   }
00424 
00425   RenWinInteractMap::iterator am_it = wins_.find (id);
00426   if (am_it != wins_.end ())
00427   {
00428     PCL_ERROR ("[addFeatureHistogram] A window with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
00429     return (false);
00430   }
00431 
00432   vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00433   xy_array->SetNumberOfComponents (2);
00434   xy_array->SetNumberOfTuples (cloud.fields[field_idx].count);
00435 
00436   // Compute the total size of the fields
00437   unsigned int fsize = 0;
00438   for (size_t i = 0; i < cloud.fields.size (); ++i)
00439     fsize += cloud.fields[i].count * pcl::getFieldSize (cloud.fields[i].datatype);
00440 
00441   // Parse the cloud data and store it in the array
00442   double xy[2];
00443   for (unsigned int d = 0; d < cloud.fields[field_idx].count; ++d)
00444   {
00445     xy[0] = d;
00446     float data;
00447     // TODO: replace float with the real data type
00448     memcpy (&data, &cloud.data[index * fsize + cloud.fields[field_idx].offset + d * sizeof (float)], sizeof (float));
00449     xy[1] = data;
00450     xy_array->SetTuple (d, xy);
00451   }
00452   RenWinInteract renwinint;
00453   createActor (xy_array, renwinint, id, win_width, win_height);
00454 
00455   // Save the pointer/ID pair to the global window map
00456   wins_[id] = renwinint;
00457 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00458   resetStoppedFlag ();
00459 #endif
00460   return (true);
00461 }
00462 
00464 bool
00465 pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram (
00466     const sensor_msgs::PointCloud2 &cloud, const std::string &field_name, 
00467     const std::string &id)
00468 {
00469   RenWinInteractMap::iterator am_it = wins_.find (id);
00470   if (am_it == wins_.end ())
00471   {
00472     PCL_WARN ("[updateFeatureHistogram] A window with id <%s> does not exists!.\n", id.c_str ());
00473     return (false);
00474   }
00475   RenWinInteract* renwinupd = &wins_[id];
00476   vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00477   xy_array->SetNumberOfComponents (2);
00478 
00479   // Get the field
00480   int field_idx = pcl::getFieldIndex (cloud, field_name);
00481   if (field_idx == -1)
00482   {
00483     pcl::console::print_error ("[updateFeatureHistogram] Invalid field (%s) given!", field_name.c_str ());
00484     return (false);
00485   }
00486   xy_array->SetNumberOfTuples (cloud.fields[field_idx].count);
00487 
00488   // Parse the cloud data and store it in the array
00489   double xy[2];
00490   for (unsigned int d = 0; d < cloud.fields[field_idx].count; ++d)
00491   {
00492     xy[0] = d;
00493     float data;
00494     memcpy (&data, &cloud.data[cloud.fields[field_idx].offset + d * sizeof (float)], sizeof (float));
00495     xy[1] = data;
00496     xy_array->SetTuple (d, xy);
00497   }
00498   reCreateActor(xy_array, renwinupd, cloud.fields[field_idx].count - 1);
00499   return (true);
00500 }
00501 
00503 bool
00504 pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram (
00505     const sensor_msgs::PointCloud2 &cloud, 
00506     const std::string &field_name, 
00507     const int index,
00508     const std::string &id)
00509 {
00510   if (index < 0 || index >= static_cast<int> (cloud.width * cloud.height))
00511   {
00512     PCL_ERROR ("[updateFeatureHistogram] Invalid point index (%d) given!\n", index);
00513     return (false);
00514   }
00515   RenWinInteractMap::iterator am_it = wins_.find (id);
00516   if (am_it == wins_.end ())
00517   {
00518     PCL_WARN ("[updateFeatureHistogram] A window with id <%s> does not exists!.\n", id.c_str ());
00519     return (false);
00520   }
00521   RenWinInteract* renwinupd = &wins_[id];
00522   vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00523   xy_array->SetNumberOfComponents (2);
00524 
00525   // Get the field
00526   int field_idx = pcl::getFieldIndex (cloud, field_name);
00527   if (field_idx == -1)
00528   {
00529     pcl::console::print_error ("[updateFeatureHistogram] Invalid field (%s) given!", field_name.c_str ());
00530     return (false);
00531   }
00532   xy_array->SetNumberOfTuples (cloud.fields[field_idx].count);
00533   
00534   // Compute the total size of the fields
00535   unsigned int fsize = 0;
00536   for (size_t i = 0; i < cloud.fields.size (); ++i)
00537     fsize += cloud.fields[i].count * pcl::getFieldSize (cloud.fields[i].datatype);
00538 
00539   // Parse the cloud data and store it in the array
00540   double xy[2];
00541   for (unsigned int d = 0; d < cloud.fields[field_idx].count; ++d)
00542   {
00543     xy[0] = d;
00544     float data;
00545     memcpy (&data, &cloud.data[index * fsize + cloud.fields[field_idx].offset + d * sizeof (float)], sizeof (float));
00546     xy[1] = data;
00547     xy_array->SetTuple (d, xy);
00548   }
00549   reCreateActor(xy_array, renwinupd, cloud.fields[field_idx].count - 1);
00550   return (true);
00551 }
00552 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:24