main_window.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-, Open Perception, 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 the copyright holder(s) 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 PCL_APPS_OPTRONIC_VIEWER_MAIN_WINDOW_H_
00039 #define PCL_APPS_OPTRONIC_VIEWER_MAIN_WINDOW_H_
00040 
00041 #include <boost/shared_ptr.hpp>
00042 
00043 #include <pcl/apps/optronic_viewer/qt.h>
00044 #include <pcl/apps/optronic_viewer/openni_grabber.h>
00045 #include <pcl/apps/optronic_viewer/cloud_filter.h>
00046 #include <pcl/io/openni_grabber.h>
00047 #include <pcl/visualization/pcl_visualizer.h>
00048 
00049 #include <fz_api.h>
00050 
00051 
00052 namespace pcl
00053 {
00054   namespace apps
00055   {
00056     namespace optronic_viewer
00057     {
00058       
00059       enum DeviceType
00060       {
00061         OPENNI_DEVICE,
00062         FOTONIC_DEVICE
00063       };
00064 
00065       class Device
00066       {
00067       public:
00068         Device (DeviceType arg_device_type)
00069           : device_type (arg_device_type)
00070         {}
00071         virtual ~Device () {}
00072 
00073         DeviceType device_type;
00074       };
00075 
00076       class OpenNIDevice
00077         : public Device
00078       {
00079       public:
00080         OpenNIDevice ()
00081           : Device (OPENNI_DEVICE)
00082         {}
00083         virtual ~OpenNIDevice () {}
00084 
00085         int device_id;
00086         std::string name;
00087         std::string vendor;
00088         std::string serial_number;
00089       };
00090 
00091       class FotonicDevice
00092         : public Device
00093       {
00094       public:
00095         FotonicDevice ()
00096           : Device (FOTONIC_DEVICE)
00097         {}
00098         virtual ~FotonicDevice () {}
00099 
00100         FZ_DEVICE_INFO device_info;
00101       };
00102 
00103 
00104       class MainWindow : public QMainWindow
00105       {
00106         Q_OBJECT
00107 
00108         public:
00109           static MainWindow& getInstance() {
00110             static MainWindow theSingleton;
00111             return theSingleton;
00112           }
00113 
00114         public slots:
00115           void selectedSensorChanged (int index);
00116           void cloud_callback (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr cloud);
00117           void refresh ();
00118           void refreshFilterList ();
00119 
00120         private:
00121           // create the file menu in the menu bar
00122           void createFileMenu ();
00123 
00124           // find connected devices
00125           void findConnectedDevices ();
00126 
00127           private slots:
00128             void addFilter ();
00129             void updateFilter (QListWidgetItem*);
00130             void filterSelectionChanged ();
00131 
00132             void moveFilterUp ();
00133             void moveFilterDown ();
00134             void removeFilter ();
00135 
00136         private:
00137           MainWindow();
00138           MainWindow(const MainWindow &) : QMainWindow () {}            // copy ctor hidden
00139           MainWindow& operator=(const MainWindow &) { return (*this); } // assign op. hidden
00140           ~MainWindow();
00141 
00142           // visualization of processing chain
00143           QListWidget * processing_list_;
00144 
00145           // buttons to change processing chain
00146           QPushButton * up_ ;
00147           QPushButton * down_;
00148           QPushButton * remove_;
00149 
00150           // visualization of point clouds
00151           QVTKWidget * qvtk_widget_;
00152           pcl::visualization::PCLVisualizer * pcl_visualizer_;
00153           pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr cloud_;
00154 
00155           // connected devices
00156           std::vector<Device*> connected_devices_;
00157 
00158           // Grabber stuff
00159           //std::vector<OpenNIDevice> connected_openni_devices_;
00160           pcl::Grabber * grabber_;
00161           pcl::apps::optronic_viewer::OpenNIGrabber * grabber_thread_;
00162 
00163           // filters
00164           std::vector<CloudFilterFactory*> filter_factories_;
00165           std::vector<CloudFilter*> active_cloud_filters_;
00166 
00167           // mutexes
00168           boost::mutex cloud_mutex_;
00169       };
00170     }
00171   }
00172 }
00173 
00174 #endif // PCL_APPS_OPTRONIC_VIEWER_MAIN_WINDOW_H_


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