#include <in_hand_scanner.h>

| Classes | |
| class | ComputationFPS | 
| Helper object for the computation thread. Please have a look at the documentation of calcFPS.  More... | |
| class | VisualizationFPS | 
| Helper object for the visualization thread. Please have a look at the documentation of calcFPS.  More... | |
| Public Types | |
| typedef pcl::ihs::OpenGLViewer | Base | 
| enum | FileType { FT_PLY = 0, FT_VTK = 1, FT_OBJ = 2, FT_MESH = 3 } | 
| File type for saving and loading files.  More... | |
| typedef enum pcl::ihs::InHandScanner::FileType | FileType | 
| File type for saving and loading files. | |
| typedef pcl::ihs::ICP | ICP | 
| typedef boost::shared_ptr < const ICP > | ICPConstPtr | 
| typedef boost::shared_ptr< ICP > | ICPPtr | 
| typedef pcl::ihs::InputDataProcessing | InputDataProcessing | 
| typedef boost::shared_ptr < const InputDataProcessing > | InputDataProcessingConstPtr | 
| typedef boost::shared_ptr < InputDataProcessing > | InputDataProcessingPtr | 
| typedef pcl::ihs::Integration | Integration | 
| typedef boost::shared_ptr < const Integration > | IntegrationConstPtr | 
| typedef boost::shared_ptr < Integration > | IntegrationPtr | 
| typedef pcl::ihs::MeshProcessing | MeshProcessing | 
| typedef boost::shared_ptr < const MeshProcessing > | MeshProcessingConstPtr | 
| typedef boost::shared_ptr < MeshProcessing > | MeshProcessingPtr | 
| enum | RunningMode { RM_SHOW_MODEL = 0, RM_UNPROCESSED = 1, RM_PROCESSED = 2, RM_REGISTRATION_CONT = 3, RM_REGISTRATION_SINGLE = 4 } | 
| Switch between different branches of the scanning pipeline.  More... | |
| typedef enum pcl::ihs::InHandScanner::RunningMode | RunningMode | 
| Switch between different branches of the scanning pipeline. | |
| typedef pcl::ihs::InHandScanner | Self | 
| Public Slots | |
| void | keyPressEvent (QKeyEvent *event) | 
| void | registerContinuously () | 
| Registers new data to the first acquired data continuously. | |
| void | registerOnce () | 
| Registers new data once and returns to showing the processed data. | |
| void | removeUnfitVertices () | 
| Removes unfit vertices regardless of their age. Unfit vertices are those that have not been observed from enough directions. | |
| void | reset () | 
| Reset the scanning pipeline. | |
| void | saveAs (const std::string &filename, const FileType &filetype) | 
| Saves the model mesh in a file with the given filename and filetype. | |
| void | showModel () | 
| Show the model shape (if one is available). | |
| void | showProcessedData () | 
| Shows the processed input data. | |
| void | showUnprocessedData () | 
| Shows the unprocessed input data. | |
| void | startGrabber () | 
| Start the grabber (enables the scanning pipeline). | |
| Signals | |
| void | runningModeChanged (RunningMode new_running_mode) const | 
| Emitted when the running mode changes. | |
| Public Member Functions | |
| ICP & | getICP () | 
| Get the registration. | |
| InputDataProcessing & | getInputDataProcessing () | 
| Get the input data processing. | |
| Integration & | getIntegration () | 
| Get the integration. | |
| InHandScanner (Base *parent=0) | |
| Constructor. | |
| ~InHandScanner () | |
| Destructor. | |
| Private Types | |
| typedef pcl::ihs::CloudIHS | CloudIHS | 
| typedef pcl::ihs::CloudIHSConstPtr | CloudIHSConstPtr | 
| typedef pcl::ihs::CloudIHSPtr | CloudIHSPtr | 
| typedef pcl::PointCloud < PointXYZRGBA > | CloudXYZRGBA | 
| typedef CloudXYZRGBA::ConstPtr | CloudXYZRGBAConstPtr | 
| typedef CloudXYZRGBA::Ptr | CloudXYZRGBAPtr | 
| typedef pcl::PointCloud < PointXYZRGBNormal > | CloudXYZRGBNormal | 
| typedef CloudXYZRGBNormal::ConstPtr | CloudXYZRGBNormalConstPtr | 
| typedef CloudXYZRGBNormal::Ptr | CloudXYZRGBNormalPtr | 
| typedef pcl::OpenNIGrabber | Grabber | 
| typedef boost::shared_ptr < const Grabber > | GrabberConstPtr | 
| typedef boost::shared_ptr < Grabber > | GrabberPtr | 
| typedef pcl::ihs::Mesh | Mesh | 
| typedef pcl::ihs::MeshConstPtr | MeshConstPtr | 
| typedef pcl::ihs::MeshPtr | MeshPtr | 
| typedef pcl::ihs::PointIHS | PointIHS | 
| typedef pcl::PointXYZRGBA | PointXYZRGBA | 
| typedef pcl::PointXYZRGBNormal | PointXYZRGBNormal | 
| Private Member Functions | |
| void | drawText () | 
| Draw text over the opengl scene. | |
| void | grab_pc (const sensor_msgs::PointCloud2::ConstPtr &msg) | 
| void | newDataCallback (const CloudXYZRGBAConstPtr &cloud_in) | 
| Called when new data arries from the grabber. The grabbing - registration - integration pipeline is implemented here. | |
| void | paintEvent (QPaintEvent *event) | 
| void | startGrabberImpl () | 
| Actual implementeation of startGrabber (needed so it can be run in a different thread and doesn't block the application when starting up). | |
| Private Attributes | |
| pcl::PointCloud < pcl::PointXYZRGBA >::Ptr | cloud_ptr_xyzrgba | 
| ComputationFPS | computation_fps_ | 
| Please have a look at the documentation of ComputationFPS. | |
| bool | destructor_called_ | 
| Prevent the application to crash while closing. | |
| GrabberPtr | grabber_ | 
| Used to get new data from the sensor. | |
| ICPPtr | icp_ | 
| Registration (Iterative Closest Point). | |
| InputDataProcessingPtr | input_data_processing_ | 
| Processes the data from the sensor. Output is input to the registration. | |
| IntegrationPtr | integration_ | 
| Integrate the data cloud into a common model. | |
| unsigned int | iteration_ | 
| The iteration of the scanning pipeline (grab - register - integrate). | |
| MeshPtr | mesh_model_ | 
| Model to which new data is registered to (stored as a mesh). | |
| MeshProcessingPtr | mesh_processing_ | 
| Methods called after the integration. | |
| boost::mutex | mutex_ | 
| Synchronization. | |
| boost::signals2::connection | new_data_connection_ | 
| Connection of the grabber signal with the data processing thread. | |
| pcl::PCLPointCloud2 | pcl_pc2 | 
| RunningMode | running_mode_ | 
| Switch between different branches of the scanning pipeline. | |
| bool | starting_grabber_ | 
| This variable is true if the grabber is starting. | |
| Eigen::Matrix4f | transformation_ | 
| Transformation that brings the data cloud into model coordinates. | |
| VisualizationFPS | visualization_fps_ | 
| Please have a look at the documentation of VisualizationFPS. | |
Definition at line 86 of file in_hand_scanner.h.
Definition at line 92 of file in_hand_scanner.h.
| typedef pcl::ihs::CloudIHS pcl::ihs::InHandScanner::CloudIHS  [private] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 213 of file in_hand_scanner.h.
| typedef pcl::ihs::CloudIHSConstPtr pcl::ihs::InHandScanner::CloudIHSConstPtr  [private] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 215 of file in_hand_scanner.h.
| typedef pcl::ihs::CloudIHSPtr pcl::ihs::InHandScanner::CloudIHSPtr  [private] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 214 of file in_hand_scanner.h.
| typedef pcl::PointCloud<PointXYZRGBA> pcl::ihs::InHandScanner::CloudXYZRGBA  [private] | 
Definition at line 203 of file in_hand_scanner.h.
| typedef CloudXYZRGBA::ConstPtr pcl::ihs::InHandScanner::CloudXYZRGBAConstPtr  [private] | 
Definition at line 205 of file in_hand_scanner.h.
| typedef CloudXYZRGBA::Ptr pcl::ihs::InHandScanner::CloudXYZRGBAPtr  [private] | 
Definition at line 204 of file in_hand_scanner.h.
| typedef pcl::PointCloud<PointXYZRGBNormal> pcl::ihs::InHandScanner::CloudXYZRGBNormal  [private] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 208 of file in_hand_scanner.h.
| typedef CloudXYZRGBNormal::ConstPtr pcl::ihs::InHandScanner::CloudXYZRGBNormalConstPtr  [private] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 210 of file in_hand_scanner.h.
| typedef CloudXYZRGBNormal::Ptr pcl::ihs::InHandScanner::CloudXYZRGBNormalPtr  [private] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 209 of file in_hand_scanner.h.
File type for saving and loading files.
| typedef pcl::OpenNIGrabber pcl::ihs::InHandScanner::Grabber  [private] | 
Definition at line 221 of file in_hand_scanner.h.
| typedef boost::shared_ptr<const Grabber> pcl::ihs::InHandScanner::GrabberConstPtr  [private] | 
Definition at line 223 of file in_hand_scanner.h.
| typedef boost::shared_ptr<Grabber> pcl::ihs::InHandScanner::GrabberPtr  [private] | 
Definition at line 222 of file in_hand_scanner.h.
Definition at line 99 of file in_hand_scanner.h.
| typedef boost::shared_ptr<const ICP> pcl::ihs::InHandScanner::ICPConstPtr | 
Definition at line 101 of file in_hand_scanner.h.
| typedef boost::shared_ptr<ICP> pcl::ihs::InHandScanner::ICPPtr | 
Definition at line 100 of file in_hand_scanner.h.
Definition at line 95 of file in_hand_scanner.h.
| typedef boost::shared_ptr<const InputDataProcessing> pcl::ihs::InHandScanner::InputDataProcessingConstPtr | 
Definition at line 97 of file in_hand_scanner.h.
| typedef boost::shared_ptr<InputDataProcessing> pcl::ihs::InHandScanner::InputDataProcessingPtr | 
Definition at line 96 of file in_hand_scanner.h.
Definition at line 103 of file in_hand_scanner.h.
| typedef boost::shared_ptr<const Integration> pcl::ihs::InHandScanner::IntegrationConstPtr | 
Definition at line 105 of file in_hand_scanner.h.
| typedef boost::shared_ptr<Integration> pcl::ihs::InHandScanner::IntegrationPtr | 
Definition at line 104 of file in_hand_scanner.h.
| typedef pcl::ihs::Mesh pcl::ihs::InHandScanner::Mesh  [private] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 217 of file in_hand_scanner.h.
| typedef pcl::ihs::MeshConstPtr pcl::ihs::InHandScanner::MeshConstPtr  [private] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 219 of file in_hand_scanner.h.
Definition at line 107 of file in_hand_scanner.h.
| typedef boost::shared_ptr<const MeshProcessing> pcl::ihs::InHandScanner::MeshProcessingConstPtr | 
Definition at line 109 of file in_hand_scanner.h.
| typedef boost::shared_ptr<MeshProcessing> pcl::ihs::InHandScanner::MeshProcessingPtr | 
Definition at line 108 of file in_hand_scanner.h.
| typedef pcl::ihs::MeshPtr pcl::ihs::InHandScanner::MeshPtr  [private] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 218 of file in_hand_scanner.h.
| typedef pcl::ihs::PointIHS pcl::ihs::InHandScanner::PointIHS  [private] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 212 of file in_hand_scanner.h.
| typedef pcl::PointXYZRGBA pcl::ihs::InHandScanner::PointXYZRGBA  [private] | 
Definition at line 202 of file in_hand_scanner.h.
| typedef pcl::PointXYZRGBNormal pcl::ihs::InHandScanner::PointXYZRGBNormal  [private] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 207 of file in_hand_scanner.h.
Switch between different branches of the scanning pipeline.
Definition at line 93 of file in_hand_scanner.h.
File type for saving and loading files.
Definition at line 122 of file in_hand_scanner.h.
Switch between different branches of the scanning pipeline.
Definition at line 112 of file in_hand_scanner.h.
| pcl::ihs::InHandScanner::InHandScanner | ( | Base * | parent = 0 | ) |  [explicit] | 
Constructor.
Definition at line 78 of file in_hand_scanner.cpp.
Destructor.
Definition at line 116 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::drawText | ( | ) |  [private] | 
Draw text over the opengl scene.
Definition at line 470 of file in_hand_scanner.cpp.
| ICP& pcl::ihs::InHandScanner::getICP | ( | ) |  [inline] | 
Get the registration.
Definition at line 144 of file in_hand_scanner.h.
Get the input data processing.
Definition at line 140 of file in_hand_scanner.h.
| Integration& pcl::ihs::InHandScanner::getIntegration | ( | ) |  [inline] | 
Get the integration.
Definition at line 148 of file in_hand_scanner.h.
| void pcl::ihs::InHandScanner::grab_pc | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) |  [private] | 
Definition at line 498 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::keyPressEvent | ( | QKeyEvent * | event | ) |  [slot] | 
Definition at line 278 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::newDataCallback | ( | const CloudXYZRGBAConstPtr & | cloud_in | ) |  [private] | 
Called when new data arries from the grabber. The grabbing - registration - integration pipeline is implemented here.
Definition at line 303 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::paintEvent | ( | QPaintEvent * | event | ) |  [private, virtual] | 
Reimplemented from pcl::ihs::OpenGLViewer.
Definition at line 445 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::registerContinuously | ( | ) |  [slot] | 
Registers new data to the first acquired data continuously.
Definition at line 168 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::registerOnce | ( | ) |  [slot] | 
Registers new data once and returns to showing the processed data.
Definition at line 184 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::removeUnfitVertices | ( | ) |  [slot] | 
Removes unfit vertices regardless of their age. Unfit vertices are those that have not been observed from enough directions.
Definition at line 214 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::reset | ( | ) |  [slot] | 
Reset the scanning pipeline.
Definition at line 238 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::runningModeChanged | ( | RunningMode | new_running_mode | ) | const  [signal] | 
Emitted when the running mode changes.
| void pcl::ihs::InHandScanner::saveAs | ( | const std::string & | filename, | 
| const FileType & | filetype | ||
| ) |  [slot] | 
Saves the model mesh in a file with the given filename and filetype.
Definition at line 258 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::showModel | ( | ) |  [slot] | 
Show the model shape (if one is available).
Definition at line 199 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::showProcessedData | ( | ) |  [slot] | 
Shows the processed input data.
Definition at line 152 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::showUnprocessedData | ( | ) |  [slot] | 
Shows the unprocessed input data.
Definition at line 136 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::startGrabber | ( | ) |  [slot] | 
Start the grabber (enables the scanning pipeline).
Definition at line 128 of file in_hand_scanner.cpp.
| void pcl::ihs::InHandScanner::startGrabberImpl | ( | ) |  [private] | 
Actual implementeation of startGrabber (needed so it can be run in a different thread and doesn't block the application when starting up).
Definition at line 512 of file in_hand_scanner.cpp.
| pcl::PointCloud<pcl::PointXYZRGBA>::Ptr pcl::ihs::InHandScanner::cloud_ptr_xyzrgba  [private] | 
Definition at line 226 of file in_hand_scanner.h.
Please have a look at the documentation of ComputationFPS.
Definition at line 278 of file in_hand_scanner.h.
| bool pcl::ihs::InHandScanner::destructor_called_  [private] | 
Prevent the application to crash while closing.
Definition at line 317 of file in_hand_scanner.h.
| GrabberPtr pcl::ihs::InHandScanner::grabber_  [private] | 
Used to get new data from the sensor.
Definition at line 290 of file in_hand_scanner.h.
| ICPPtr pcl::ihs::InHandScanner::icp_  [private] | 
Registration (Iterative Closest Point).
Definition at line 302 of file in_hand_scanner.h.
Processes the data from the sensor. Output is input to the registration.
Definition at line 299 of file in_hand_scanner.h.
Integrate the data cloud into a common model.
Definition at line 308 of file in_hand_scanner.h.
| unsigned int pcl::ihs::InHandScanner::iteration_  [private] | 
The iteration of the scanning pipeline (grab - register - integrate).
Definition at line 287 of file in_hand_scanner.h.
| MeshPtr pcl::ihs::InHandScanner::mesh_model_  [private] | 
Model to which new data is registered to (stored as a mesh).
Definition at line 314 of file in_hand_scanner.h.
Methods called after the integration.
Definition at line 311 of file in_hand_scanner.h.
| boost::mutex pcl::ihs::InHandScanner::mutex_  [private] | 
Synchronization.
Definition at line 275 of file in_hand_scanner.h.
| boost::signals2::connection pcl::ihs::InHandScanner::new_data_connection_  [private] | 
Connection of the grabber signal with the data processing thread.
Definition at line 296 of file in_hand_scanner.h.
| pcl::PCLPointCloud2 pcl::ihs::InHandScanner::pcl_pc2  [private] | 
Definition at line 225 of file in_hand_scanner.h.
Switch between different branches of the scanning pipeline.
Definition at line 284 of file in_hand_scanner.h.
| bool pcl::ihs::InHandScanner::starting_grabber_  [private] | 
This variable is true if the grabber is starting.
Definition at line 293 of file in_hand_scanner.h.
| Eigen::Matrix4f pcl::ihs::InHandScanner::transformation_  [private] | 
Transformation that brings the data cloud into model coordinates.
Definition at line 305 of file in_hand_scanner.h.
Please have a look at the documentation of VisualizationFPS.
Definition at line 281 of file in_hand_scanner.h.