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  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: interactor.cpp 1829 2011-07-18 19:26:51Z mdixon $
00037  *
00038  */
00039 
00040 #include <pcl/visualization/point_picking_event.h>
00041 #include <pcl/visualization/interactor_style.h>
00042 #include <vtkPointPicker.h>
00043 #include <vtkRendererCollection.h>
00044 
00046 void
00047 pcl::visualization::PointPickingCallback::Execute (vtkObject *caller, unsigned long eventid, void*)
00048 {
00049   vtkRenderWindowInteractor* iren = reinterpret_cast<pcl::visualization::PCLVisualizerInteractorStyle*>(caller)->GetInteractor ();
00050 
00051   if ((eventid == vtkCommand::LeftButtonPressEvent) && (iren->GetShiftKey () > 0)) 
00052   {
00053     float x = 0, y = 0, z = 0;
00054     int idx = performSinglePick (iren, x, y, z);
00055     // Create a PointPickingEvent
00056     PointPickingEvent event (idx, x, y, z);
00057     reinterpret_cast<pcl::visualization::PCLVisualizerInteractorStyle*>(caller)->point_picking_signal_ (event);
00058   }
00059   else if ((eventid == vtkCommand::LeftButtonPressEvent) && (iren->GetAltKey () == 1))
00060   {
00061     pick_first_ = !pick_first_;
00062     float x = 0, y = 0, z = 0;
00063     int idx = -1;
00064     if (pick_first_)
00065       idx_ = performSinglePick (iren, x_, y_, z_);
00066     else
00067       idx = performSinglePick (iren, x, y, z);
00068     // Create a PointPickingEvent
00069     PointPickingEvent event (idx_, idx, x_, y_, z_, x, y, z);
00070     reinterpret_cast<pcl::visualization::PCLVisualizerInteractorStyle*>(caller)->point_picking_signal_ (event);
00071   }
00072   // Call the parent's class mouse events
00073   reinterpret_cast<pcl::visualization::PCLVisualizerInteractorStyle*>(caller)->OnLeftButtonDown ();
00074 }
00075 
00077 int
00078 pcl::visualization::PointPickingCallback::performSinglePick (vtkRenderWindowInteractor *iren)
00079 {
00080   int mouse_x, mouse_y;
00081   vtkPointPicker *picker = (vtkPointPicker*)iren->GetPicker ();
00082   //iren->GetMousePosition (&mouse_x, &mouse_y);
00083   mouse_x = iren->GetEventPosition ()[0];
00084   mouse_y = iren->GetEventPosition ()[1];
00085   iren->StartPickCallback ();
00086   
00087   vtkRenderer *ren = iren->FindPokedRenderer (iren->GetEventPosition ()[0], iren->GetEventPosition ()[1]);
00088   picker->Pick (mouse_x, mouse_y, 0.0, ren);
00089   return ((int)picker->GetPointId ());
00090 }
00091 
00093 int
00094 pcl::visualization::PointPickingCallback::performSinglePick (
00095     vtkRenderWindowInteractor *iren,
00096     float &x, float &y, float &z)
00097 {
00098   int mouse_x, mouse_y;
00099   vtkPointPicker *picker = (vtkPointPicker*)iren->GetPicker ();
00100   //iren->GetMousePosition (&mouse_x, &mouse_y);
00101   mouse_x = iren->GetEventPosition ()[0];
00102   mouse_y = iren->GetEventPosition ()[1];
00103   iren->StartPickCallback ();
00104   
00105   vtkRenderer *ren = iren->FindPokedRenderer (iren->GetEventPosition ()[0], iren->GetEventPosition ()[1]);
00106   picker->Pick (mouse_x, mouse_y, 0.0, ren);
00107 
00108   int idx = picker->GetPointId ();
00109   if (picker->GetDataSet () != NULL)
00110   {
00111     double p[3];
00112     picker->GetDataSet ()->GetPoint (idx, p);
00113     x = p[0]; y = p[1]; z = p[2];
00114   }
00115   return (idx);
00116 }
00117 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:19