00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Point Cloud Library (PCL) - www.pointclouds.org 00005 * Copyright (c) 2009-2012, 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 * $Id$ 00038 * 00039 */ 00040 00041 #ifndef PCL_APPS_IN_HAND_SCANNER_IN_HAND_SCANNER_H 00042 #define PCL_APPS_IN_HAND_SCANNER_IN_HAND_SCANNER_H 00043 00044 #include <string> 00045 #include <sstream> 00046 #include <iomanip> 00047 00048 #include <pcl/pcl_exports.h> 00049 #include <pcl/apps/in_hand_scanner/boost.h> 00050 #include <pcl/apps/in_hand_scanner/common_types.h> 00051 #include <pcl/apps/in_hand_scanner/opengl_viewer.h> 00052 00054 // Forward declarations 00056 00057 namespace pcl 00058 { 00059 class OpenNIGrabber; 00060 00061 namespace ihs 00062 { 00063 class ICP; 00064 class InputDataProcessing; 00065 class Integration; 00066 class MeshProcessing; 00067 } // End namespace ihs 00068 } // End namespace pcl 00069 00071 // InHandScanner 00073 00074 namespace pcl 00075 { 00076 namespace ihs 00077 { 00081 class PCL_EXPORTS InHandScanner : public pcl::ihs::OpenGLViewer 00082 { 00083 Q_OBJECT 00084 00085 public: 00086 00087 typedef pcl::ihs::OpenGLViewer Base; 00088 typedef pcl::ihs::InHandScanner Self; 00089 00090 typedef pcl::ihs::InputDataProcessing InputDataProcessing; 00091 typedef boost::shared_ptr <InputDataProcessing> InputDataProcessingPtr; 00092 typedef boost::shared_ptr <const InputDataProcessing> InputDataProcessingConstPtr; 00093 00094 typedef pcl::ihs::ICP ICP; 00095 typedef boost::shared_ptr <ICP> ICPPtr; 00096 typedef boost::shared_ptr <const ICP> ICPConstPtr; 00097 00098 typedef pcl::ihs::Integration Integration; 00099 typedef boost::shared_ptr <Integration> IntegrationPtr; 00100 typedef boost::shared_ptr <const Integration> IntegrationConstPtr; 00101 00102 typedef pcl::ihs::MeshProcessing MeshProcessing; 00103 typedef boost::shared_ptr <MeshProcessing> MeshProcessingPtr; 00104 typedef boost::shared_ptr <const MeshProcessing> MeshProcessingConstPtr; 00105 00107 typedef enum RunningMode 00108 { 00109 RM_SHOW_MODEL = 0, 00110 RM_UNPROCESSED = 1, 00111 RM_PROCESSED = 2, 00112 RM_REGISTRATION_CONT = 3, 00113 RM_REGISTRATION_SINGLE = 4 00114 } RunningMode; 00115 00117 typedef enum FileType 00118 { 00119 FT_PLY = 0, 00120 FT_VTK = 1 00121 } FileType; 00122 00124 explicit InHandScanner (Base* parent=0); 00125 00127 ~InHandScanner (); 00128 00130 inline InputDataProcessing& 00131 getInputDataProcessing () {return (*input_data_processing_);} 00132 00134 inline ICP& 00135 getICP () {return (*icp_);} 00136 00138 inline Integration& 00139 getIntegration () {return (*integration_);} 00140 00141 signals: 00142 00144 void 00145 runningModeChanged (RunningMode new_running_mode) const; 00146 00147 public slots: 00148 00150 void 00151 startGrabber (); 00152 00154 void 00155 showUnprocessedData (); 00156 00158 void 00159 showProcessedData (); 00160 00162 void 00163 registerContinuously (); 00164 00166 void 00167 registerOnce (); 00168 00170 void 00171 showModel (); 00172 00174 void 00175 removeUnfitVertices (); 00176 00178 void 00179 reset (); 00180 00184 void 00185 saveAs (const std::string& filename, const FileType& filetype); 00186 00188 void 00189 keyPressEvent (QKeyEvent* event); 00190 00191 private: 00192 00193 typedef pcl::PointXYZRGBA PointXYZRGBA; 00194 typedef pcl::PointCloud <PointXYZRGBA> CloudXYZRGBA; 00195 typedef CloudXYZRGBA::Ptr CloudXYZRGBAPtr; 00196 typedef CloudXYZRGBA::ConstPtr CloudXYZRGBAConstPtr; 00197 00198 typedef pcl::PointXYZRGBNormal PointXYZRGBNormal; 00199 typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal; 00200 typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr; 00201 typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr; 00202 00203 typedef pcl::ihs::PointIHS PointIHS; 00204 typedef pcl::ihs::CloudIHS CloudIHS; 00205 typedef pcl::ihs::CloudIHSPtr CloudIHSPtr; 00206 typedef pcl::ihs::CloudIHSConstPtr CloudIHSConstPtr; 00207 00208 typedef pcl::ihs::Mesh Mesh; 00209 typedef pcl::ihs::MeshPtr MeshPtr; 00210 typedef pcl::ihs::MeshConstPtr MeshConstPtr; 00211 00212 typedef pcl::OpenNIGrabber Grabber; 00213 typedef boost::shared_ptr <Grabber> GrabberPtr; 00214 typedef boost::shared_ptr <const Grabber> GrabberConstPtr; 00215 00217 class ComputationFPS : public Base::FPS 00218 { 00219 public: 00220 ComputationFPS () : Base::FPS () {} 00221 ~ComputationFPS () {} 00222 }; 00223 00225 class VisualizationFPS : public Base::FPS 00226 { 00227 public: 00228 VisualizationFPS () : Base::FPS () {} 00229 ~VisualizationFPS () {} 00230 }; 00231 00233 void 00234 newDataCallback (const CloudXYZRGBAConstPtr& cloud_in); 00235 00239 void 00240 paintEvent (QPaintEvent* event); 00241 00245 void 00246 drawText (); 00247 00249 void 00250 startGrabberImpl (); 00251 00253 // Members 00255 00257 boost::mutex mutex_; 00258 00260 ComputationFPS computation_fps_; 00261 00263 VisualizationFPS visualization_fps_; 00264 00266 RunningMode running_mode_; 00267 00269 unsigned int iteration_; 00270 00272 GrabberPtr grabber_; 00273 00275 bool starting_grabber_; 00276 00278 boost::signals2::connection new_data_connection_; 00279 00281 InputDataProcessingPtr input_data_processing_; 00282 00284 ICPPtr icp_; 00285 00287 Eigen::Matrix4f transformation_; 00288 00290 IntegrationPtr integration_; 00291 00293 MeshProcessingPtr mesh_processing_; 00294 00296 MeshPtr mesh_model_; 00297 00299 bool destructor_called_; 00300 00301 public: 00302 00303 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00304 }; 00305 } // End namespace ihs 00306 } // End namespace pcl 00307 00308 // http://doc.qt.digia.com/qt/qmetatype.html#Q_DECLARE_METATYPE 00309 Q_DECLARE_METATYPE (pcl::ihs::InHandScanner::RunningMode) 00310 00311 #endif // PCL_APPS_IN_HAND_SCANNER_IN_HAND_SCANNER_H