interactor_style_switch.h
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) 2012, Jeremie Papon.
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  */
00037 
00038 #ifndef INTERACTOR_STYLE_SWITCH_H_
00039 #define INTERACTOR_STYLE_SWITCH_H_
00040 
00041 #include <pcl/visualization/vtk.h>
00042 #include <pcl/visualization/interactor_style.h>
00043 #include <pcl/visualization/common/actor_map.h>
00044 #include <pcl/visualization/common/ren_win_interact_map.h>
00045 #include <pcl/visualization/pcl_visualizer.h>
00046 
00047 #include <pcl/apps/cloud_composer/qt.h>
00048 
00049 
00050 
00051 
00052 
00053 namespace pcl
00054 {
00055   namespace cloud_composer
00056   {
00057     namespace interactor_styles
00058     {
00059       enum INTERACTOR_STYLES
00060       { 
00061         PCL_VISUALIZER = 0,
00062         RECTANGULAR_FRUSTUM,
00063         SELECTED_TRACKBALL,
00064         CLICK_TRACKBALL
00065       };
00066     }
00067     namespace interactor_events
00068     {
00069       enum 
00070       {
00071         SELECTION_COMPLETE_EVENT = vtkCommand::UserEvent + 1,
00072         MANIPULATION_COMPLETE_EVENT
00073       };
00074     };
00075 
00076     class RectangularFrustumSelector;  
00077     class SelectedTrackballStyleInteractor;
00078     class ClickTrackballStyleInteractor;
00079     class ProjectModel;
00080     
00081     class PCL_EXPORTS InteractorStyleSwitch : public vtkInteractorStyle 
00082     {
00083       public:
00084         static InteractorStyleSwitch *New();
00085         vtkTypeMacro(InteractorStyleSwitch, vtkInteractorStyle);
00086         
00087         InteractorStyleSwitch();
00088         virtual ~InteractorStyleSwitch();
00089   
00090         void 
00091         SetInteractor(vtkRenderWindowInteractor *iren);
00092         
00093         vtkGetObjectMacro(current_style_, vtkInteractorStyle);
00094         
00095         void 
00096         initializeInteractorStyles (boost::shared_ptr<pcl::visualization::PCLVisualizer> vis, ProjectModel* model);
00097         
00098         inline void 
00099         setQVTKWidget (QVTKWidget* qvtk) { qvtk_ = qvtk; }
00100                 
00101         void
00102         setCurrentInteractorStyle (interactor_styles::INTERACTOR_STYLES interactor_style);
00103         
00104       //  vtkSmartPointer<pcl::visualization::PCLVisualizerInteractorStyle>
00105       //  getPCLVisInteractorStyle () { return pcl_vis_style_; }
00106         
00107         inline vtkSmartPointer <vtkInteractorStyle>
00108         getInteractorStyle (const interactor_styles::INTERACTOR_STYLES interactor_style) const 
00109           { return name_to_style_map_.value (interactor_style); }
00110         
00111         virtual 
00112         void SetDefaultRenderer(vtkRenderer*);
00113         virtual 
00114         void SetCurrentRenderer(vtkRenderer*);
00115         
00116         virtual void
00117         OnLeave ();
00118                   
00119       protected:
00120         void 
00121         setCurrentStyle();
00122         
00123         QMap <interactor_styles::INTERACTOR_STYLES, vtkSmartPointer <vtkInteractorStyle> > name_to_style_map_;
00124         
00125         
00126         vtkRenderWindowInteractor* render_window_interactor_;
00127         vtkSmartPointer<vtkRendererCollection> rens_;
00128         
00129         vtkSmartPointer<vtkInteractorStyle> current_style_;
00130         vtkSmartPointer<pcl::visualization::PCLVisualizerInteractorStyle> pcl_vis_style_;
00131         vtkSmartPointer<RectangularFrustumSelector> rectangular_frustum_selector_;
00132         
00133         vtkSmartPointer<SelectedTrackballStyleInteractor> selected_trackball_interactor_style_;
00134         
00135         vtkSmartPointer<ClickTrackballStyleInteractor> click_trackball_interactor_style_;
00136         vtkSmartPointer<vtkAreaPicker> area_picker_;
00137         vtkSmartPointer<vtkPointPicker> point_picker_;
00138         
00140         QVTKWidget* qvtk_;
00142         boost::shared_ptr<pcl::visualization::PCLVisualizer> vis_;
00143       private:
00144         InteractorStyleSwitch(const InteractorStyleSwitch&);  // Not implemented.
00145         void operator=(const InteractorStyleSwitch&);  // Not implemented.
00146         ProjectModel* project_model_;
00147     };
00148     
00149   }
00150   
00151 }
00152 
00153 #endif // INTERACTOR_STYLE_SWITCH_H_
00154         
00155         


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