cloud_view.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 CLOUD_VIEW_H_
00039 #define CLOUD_VIEW_H_
00040 
00041 #include <pcl/apps/cloud_composer/qt.h>
00042 #include <pcl/visualization/pcl_visualizer.h>
00043 #include <pcl/apps/cloud_composer/point_selectors/interactor_style_switch.h>
00044 #include <vtkEventQtSlotConnect.h>
00045 
00046 namespace pcl
00047 {
00048   namespace cloud_composer
00049   {
00050     class ProjectModel;
00055     class CloudView : public QWidget
00056     {
00057       Q_OBJECT
00058       
00059     public:
00060       CloudView (QWidget* parent = 0);
00061       CloudView (const CloudView& to_copy);
00062       CloudView (ProjectModel* model, QWidget* parent = 0);
00063       virtual ~CloudView ();
00064       
00065       void 
00066       setModel (ProjectModel* new_model);
00067       ProjectModel* 
00068       getModel () const { return model_; }
00069       
00070       QVTKWidget* 
00071       getQVTK() const {return qvtk_; }
00072       
00073       boost::shared_ptr<pcl::visualization::PCLVisualizer>
00074       getPCLVisualizer () const { return vis_; }
00075       
00076       void 
00077       setAxisVisibility (bool visible);
00078       
00079       void 
00080       setInteractorStyle (interactor_styles::INTERACTOR_STYLES style);
00081     public slots:
00082       void 
00083       refresh ();
00084       
00086       void 
00087       selectedItemChanged (const QItemSelection & selected, const QItemSelection & deselected);
00088       
00090       void 
00091       dataChanged ( const QModelIndex & topLeft, const QModelIndex & bottomRight );
00092       
00093     protected slots:
00098       void
00099       itemChanged (QStandardItem* item);
00100       
00105       void
00106       rowsInserted (const QModelIndex& parent, int start, int end);
00107       
00108       void
00109       rowsAboutToBeRemoved (const QModelIndex& parent, int start, int end);
00110       
00111       void
00112       selectionCompleted (vtkObject* caller, unsigned long event_id, void* client_data, void* call_data);
00113       
00114       void
00115       manipulationCompleted (vtkObject* caller, unsigned long event_id, void* client_data, void* call_data);
00116       
00117     protected:
00118       void
00119       paintEvent (QPaintEvent* event);
00120       void 
00121       resizeEvent (QResizeEvent* event);
00122       //   void scrollContentsBy (int dx, int dy);
00123       
00124       
00125       
00126     private:
00127       void
00128       connectSignalsAndSlots ();
00129       
00131       void 
00132       initializeInteractorSwitch ();
00133       
00134       void
00135       addOrientationMarkerWidgetAxes ();
00136       void
00137       removeOrientationMarkerWidgetAxes ();
00138       
00139       boost::shared_ptr<pcl::visualization::PCLVisualizer> vis_;
00140       ProjectModel* model_;
00141       QVTKWidget* qvtk_;
00142       vtkSmartPointer<InteractorStyleSwitch> style_switch_;
00143       
00144       vtkSmartPointer<vtkOrientationMarkerWidget> axes_widget_;
00145       vtkSmartPointer<vtkAxesActor> axes_;
00146       
00148       vtkSmartPointer<vtkEventQtSlotConnect> connections_;
00149     };
00150   }
00151 }
00152 
00153 Q_DECLARE_METATYPE (pcl::cloud_composer::CloudView);
00154 #endif


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:46