point_picking_event.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-2011, 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/visualization/point_picking_event.h>
00040 #include <pcl/visualization/interactor_style.h>
00041 #include <vtkPointPicker.h>
00042 #include <vtkAreaPicker.h>
00043 #include <vtkRenderWindowInteractor.h>
00044 #include <vtkDataSet.h>
00045 #include <vtkPolyData.h>
00046 #include <vtkIdTypeArray.h>
00047 #include <vtkExtractGeometry.h>
00048 #include <vtkPointData.h>
00049 #include <vtkVertexGlyphFilter.h>
00050 #include <vtkPlanes.h>
00051 #include <vtkXYPlotActor.h>
00052 #include <vtkRenderer.h>
00053 #include <vtkRenderWindow.h>
00054 
00056 void
00057 pcl::visualization::PointPickingCallback::Execute (vtkObject *caller, unsigned long eventid, void*)
00058 {
00059   PCLVisualizerInteractorStyle *style = reinterpret_cast<PCLVisualizerInteractorStyle*>(caller);
00060   vtkRenderWindowInteractor* iren = reinterpret_cast<pcl::visualization::PCLVisualizerInteractorStyle*>(caller)->GetInteractor ();
00061   if (style->CurrentMode == 0)
00062   {
00063     if ((eventid == vtkCommand::LeftButtonPressEvent) && (iren->GetShiftKey () > 0))
00064     {
00065       float x = 0, y = 0, z = 0;
00066       int idx = performSinglePick (iren, x, y, z);
00067       // Create a PointPickingEvent if a point was selected
00068       if (idx != -1)
00069       {
00070         PointPickingEvent event (idx, x, y, z);
00071         style->point_picking_signal_ (event);
00072       }
00073     }
00074     else if ((eventid == vtkCommand::LeftButtonPressEvent) && (iren->GetAltKey () == 1))
00075     {
00076       pick_first_ = !pick_first_;
00077       float x = 0, y = 0, z = 0;
00078       int idx = -1;
00079       if (pick_first_)
00080         idx_ = performSinglePick (iren, x_, y_, z_);
00081       else
00082         idx = performSinglePick (iren, x, y, z);
00083       // Create a PointPickingEvent
00084       PointPickingEvent event (idx_, idx, x_, y_, z_, x, y, z);
00085       style->point_picking_signal_ (event);
00086     }
00087     // Call the parent's class mouse events
00088     if (eventid == vtkCommand::LeftButtonPressEvent)
00089       style->OnLeftButtonDown ();
00090     else if (eventid == vtkCommand::LeftButtonReleaseEvent)
00091       style->OnLeftButtonUp ();
00092   }
00093   else
00094   {
00095     if (eventid == vtkCommand::LeftButtonPressEvent)
00096     {
00097       style->OnLeftButtonDown ();
00098       x_ = static_cast<float> (iren->GetEventPosition ()[0]);
00099       y_ = static_cast<float> (iren->GetEventPosition ()[1]);
00100     }
00101     else if (eventid == vtkCommand::LeftButtonReleaseEvent)
00102     {
00103       style->OnLeftButtonUp ();
00104       std::vector<int> indices;
00105       int nb_points = performAreaPick (iren, indices);
00106       AreaPickingEvent event (nb_points, indices);
00107       style->area_picking_signal_ (event);
00108     }
00109   }
00110 }
00111 
00113 int
00114 pcl::visualization::PointPickingCallback::performSinglePick (vtkRenderWindowInteractor *iren)
00115 {
00116   vtkPointPicker* point_picker = vtkPointPicker::SafeDownCast (iren->GetPicker ());
00117   
00118   if (!point_picker)
00119   {
00120     pcl::console::print_error ("Point picker not available, not selecting any points!\n");
00121     return -1;
00122   }
00123 
00124   int mouse_x = iren->GetEventPosition ()[0];
00125   int mouse_y = iren->GetEventPosition ()[1];
00126 
00127   iren->StartPickCallback ();
00128   vtkRenderer *ren = iren->FindPokedRenderer (mouse_x, mouse_y);
00129   point_picker->Pick (mouse_x, mouse_y, 0.0, ren);
00130 
00131   return (static_cast<int> (point_picker->GetPointId ()));
00132 }
00133 
00135 int
00136 pcl::visualization::PointPickingCallback::performSinglePick (
00137     vtkRenderWindowInteractor *iren,
00138     float &x, float &y, float &z)
00139 {
00140   vtkPointPicker* point_picker = vtkPointPicker::SafeDownCast (iren->GetPicker ());
00141 
00142   if (!point_picker)
00143   {
00144     pcl::console::print_error ("Point picker not available, not selecting any points!\n");
00145     return (-1);
00146   }
00147 
00148   int mouse_x = iren->GetEventPosition ()[0];
00149   int mouse_y = iren->GetEventPosition ()[1];
00150 
00151   iren->StartPickCallback ();
00152   vtkRenderer *ren = iren->FindPokedRenderer (mouse_x, mouse_y);
00153   point_picker->Pick (mouse_x, mouse_y, 0.0, ren);
00154 
00155   int idx = static_cast<int> (point_picker->GetPointId ());
00156   if (point_picker->GetDataSet () != NULL)
00157   {
00158     double p[3];
00159     point_picker->GetDataSet ()->GetPoint (idx, p);
00160     x = float (p[0]); y = float (p[1]); z = float (p[2]);
00161   }
00162 
00163   return (idx);
00164 }
00165 
00167 int
00168 pcl::visualization::PointPickingCallback::performAreaPick (vtkRenderWindowInteractor *iren,
00169                                                            std::vector<int> &indices)
00170 {
00171   vtkAreaPicker *picker = static_cast<vtkAreaPicker*> (iren->GetPicker ());
00172   vtkRenderer *ren = iren->FindPokedRenderer (iren->GetEventPosition ()[0], iren->GetEventPosition ()[1]);
00173   picker->AreaPick (x_, y_, iren->GetEventPosition ()[0], iren->GetEventPosition ()[1], ren);
00174   if (picker->GetDataSet ())
00175   {
00176     vtkPolyData* points = reinterpret_cast<vtkPolyData*> (picker->GetDataSet ());
00177 
00178     // This is a naive solution till we fugure out where to add the GlobalIds at an earlier stage
00179     if (!points->GetPointData ()->GetGlobalIds () ||
00180         points->GetPointData ()->GetGlobalIds ()->GetNumberOfTuples () == 0)
00181     {
00182       vtkSmartPointer<vtkIdTypeArray> global_ids = vtkIdTypeArray::New ();
00183       global_ids->SetNumberOfValues (picker->GetDataSet ()->GetNumberOfPoints ());
00184       for (vtkIdType i = 0; i < picker->GetDataSet ()->GetNumberOfPoints (); ++i)
00185         global_ids->SetValue (i,i);
00186 
00187       points->GetPointData ()->SetGlobalIds (global_ids);
00188     }
00189 
00190     vtkPlanes* frustum = picker->GetFrustum ();
00191 
00192     vtkSmartPointer<vtkExtractGeometry> extract_geometry = vtkSmartPointer<vtkExtractGeometry>::New ();
00193     extract_geometry->SetImplicitFunction (frustum);
00194 
00195 #if VTK_MAJOR_VERSION <= 5
00196     extract_geometry->SetInput (picker->GetDataSet ());
00197 #else
00198     extract_geometry->SetInputData (picker->GetDataSet ());
00199 #endif
00200 
00201     extract_geometry->Update ();
00202 
00203     vtkSmartPointer<vtkVertexGlyphFilter> glyph_filter = vtkSmartPointer<vtkVertexGlyphFilter>::New ();
00204     glyph_filter->SetInputConnection (extract_geometry->GetOutputPort ());
00205     glyph_filter->Update ();
00206 
00207     vtkPolyData* selected = glyph_filter->GetOutput ();
00208     vtkIdTypeArray* ids = vtkIdTypeArray::SafeDownCast(selected->GetPointData ()->GetGlobalIds ());
00209     assert (ids);
00210     indices.reserve (ids->GetNumberOfTuples ());
00211 
00212     for(vtkIdType i = 0; i < ids->GetNumberOfTuples (); i++)
00213       indices.push_back (static_cast<int> (ids->GetValue (i)));
00214 
00215     return (static_cast<int> (selected->GetNumberOfPoints ()));
00216   }
00217   return (-1);
00218 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:31:02