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 00053 #include <pcl/PCLPointCloud2.h> 00054 00055 #include <ros/ros.h> 00056 #include "sensor_msgs/PointCloud2.h" 00057 00059 // Forward declarations 00061 00062 namespace pcl 00063 { 00064 class OpenNIGrabber; 00065 00066 namespace ihs 00067 { 00068 class ICP; 00069 class InputDataProcessing; 00070 class Integration; 00071 class MeshProcessing; 00072 } // End namespace ihs 00073 } // End namespace pcl 00074 00076 // InHandScanner 00078 00079 namespace pcl 00080 { 00081 namespace ihs 00082 { 00086 class PCL_EXPORTS InHandScanner : public pcl::ihs::OpenGLViewer 00087 { 00088 Q_OBJECT 00089 00090 public: 00091 00092 typedef pcl::ihs::OpenGLViewer Base; 00093 typedef pcl::ihs::InHandScanner Self; 00094 00095 typedef pcl::ihs::InputDataProcessing InputDataProcessing; 00096 typedef boost::shared_ptr <InputDataProcessing> InputDataProcessingPtr; 00097 typedef boost::shared_ptr <const InputDataProcessing> InputDataProcessingConstPtr; 00098 00099 typedef pcl::ihs::ICP ICP; 00100 typedef boost::shared_ptr <ICP> ICPPtr; 00101 typedef boost::shared_ptr <const ICP> ICPConstPtr; 00102 00103 typedef pcl::ihs::Integration Integration; 00104 typedef boost::shared_ptr <Integration> IntegrationPtr; 00105 typedef boost::shared_ptr <const Integration> IntegrationConstPtr; 00106 00107 typedef pcl::ihs::MeshProcessing MeshProcessing; 00108 typedef boost::shared_ptr <MeshProcessing> MeshProcessingPtr; 00109 typedef boost::shared_ptr <const MeshProcessing> MeshProcessingConstPtr; 00110 00112 typedef enum RunningMode 00113 { 00114 RM_SHOW_MODEL = 0, 00115 RM_UNPROCESSED = 1, 00116 RM_PROCESSED = 2, 00117 RM_REGISTRATION_CONT = 3, 00118 RM_REGISTRATION_SINGLE = 4 00119 } RunningMode; 00120 00122 typedef enum FileType 00123 { 00124 FT_PLY = 0, 00125 //FT_PLY_BIN = 1 00126 FT_VTK = 1, 00127 FT_OBJ = 2, 00128 FT_MESH = 3 00129 00130 } FileType; 00131 00133 explicit InHandScanner (Base* parent=0); 00134 00136 ~InHandScanner (); 00137 00139 inline InputDataProcessing& 00140 getInputDataProcessing () {return (*input_data_processing_);} 00141 00143 inline ICP& 00144 getICP () {return (*icp_);} 00145 00147 inline Integration& 00148 getIntegration () {return (*integration_);} 00149 00150 signals: 00151 00153 void 00154 runningModeChanged (RunningMode new_running_mode) const; 00155 00156 public slots: 00157 00159 void 00160 startGrabber (); 00161 00163 void 00164 showUnprocessedData (); 00165 00167 void 00168 showProcessedData (); 00169 00171 void 00172 registerContinuously (); 00173 00175 void 00176 registerOnce (); 00177 00179 void 00180 showModel (); 00181 00183 void 00184 removeUnfitVertices (); 00185 00187 void 00188 reset (); 00189 00193 void 00194 saveAs (const std::string& filename, const FileType& filetype); 00195 00197 void 00198 keyPressEvent (QKeyEvent* event); 00199 00200 private: 00201 00202 typedef pcl::PointXYZRGBA PointXYZRGBA; 00203 typedef pcl::PointCloud <PointXYZRGBA> CloudXYZRGBA; 00204 typedef CloudXYZRGBA::Ptr CloudXYZRGBAPtr; 00205 typedef CloudXYZRGBA::ConstPtr CloudXYZRGBAConstPtr; 00206 00207 typedef pcl::PointXYZRGBNormal PointXYZRGBNormal; 00208 typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal; 00209 typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr; 00210 typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr; 00211 00212 typedef pcl::ihs::PointIHS PointIHS; 00213 typedef pcl::ihs::CloudIHS CloudIHS; 00214 typedef pcl::ihs::CloudIHSPtr CloudIHSPtr; 00215 typedef pcl::ihs::CloudIHSConstPtr CloudIHSConstPtr; 00216 00217 typedef pcl::ihs::Mesh Mesh; 00218 typedef pcl::ihs::MeshPtr MeshPtr; 00219 typedef pcl::ihs::MeshConstPtr MeshConstPtr; 00220 00221 typedef pcl::OpenNIGrabber Grabber; 00222 typedef boost::shared_ptr <Grabber> GrabberPtr; 00223 typedef boost::shared_ptr <const Grabber> GrabberConstPtr; 00224 00225 pcl::PCLPointCloud2 pcl_pc2; 00226 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud_ptr_xyzrgba; 00227 00229 class ComputationFPS : public Base::FPS 00230 { 00231 public: 00232 ComputationFPS () : Base::FPS () {} 00233 ~ComputationFPS () {} 00234 }; 00235 00237 class VisualizationFPS : public Base::FPS 00238 { 00239 public: 00240 VisualizationFPS () : Base::FPS () {} 00241 ~VisualizationFPS () {} 00242 }; 00243 00245 void 00246 newDataCallback (const CloudXYZRGBAConstPtr& cloud_in); 00247 00253 void 00254 grab_pc(const sensor_msgs::PointCloud2::ConstPtr &msg); 00255 00256 00257 void 00258 paintEvent (QPaintEvent* event); 00259 00263 void 00264 drawText (); 00265 00267 void 00268 startGrabberImpl (); 00269 00271 // Members 00273 00275 boost::mutex mutex_; 00276 00278 ComputationFPS computation_fps_; 00279 00281 VisualizationFPS visualization_fps_; 00282 00284 RunningMode running_mode_; 00285 00287 unsigned int iteration_; 00288 00290 GrabberPtr grabber_; 00291 00293 bool starting_grabber_; 00294 00296 boost::signals2::connection new_data_connection_; 00297 00299 InputDataProcessingPtr input_data_processing_; 00300 00302 ICPPtr icp_; 00303 00305 Eigen::Matrix4f transformation_; 00306 00308 IntegrationPtr integration_; 00309 00311 MeshProcessingPtr mesh_processing_; 00312 00314 MeshPtr mesh_model_; 00315 00317 bool destructor_called_; 00318 00319 public: 00320 00321 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00322 }; 00323 } // End namespace ihs 00324 } // End namespace pcl 00325 00326 // http://doc.qt.digia.com/qt/qmetatype.html#Q_DECLARE_METATYPE 00327 Q_DECLARE_METATYPE (pcl::ihs::InHandScanner::RunningMode) 00328 00329 #endif // PCL_APPS_IN_HAND_SCANNER_IN_HAND_SCANNER_H