Viewer for the in-hand scanner based on Qt and OpenGL. More...
#include <opengl_viewer.h>
Classes | |
class | BoxCoefficients |
Coefficients for the wireframe box. More... | |
class | FPS |
Please have a look at the documentation of calcFPS. More... | |
Public Types | |
typedef pcl::PointCloud < PointXYZRGBNormal > | CloudXYZRGBNormal |
typedef CloudXYZRGBNormal::ConstPtr | CloudXYZRGBNormalConstPtr |
typedef CloudXYZRGBNormal::Ptr | CloudXYZRGBNormalPtr |
enum | Coloring { COL_RGB, COL_ONE_COLOR, COL_VISCONF } |
How to color the shapes. More... | |
typedef enum pcl::ihs::OpenGLViewer::Coloring | Coloring |
How to color the shapes. | |
typedef pcl::ihs::Mesh | Mesh |
typedef pcl::ihs::MeshConstPtr | MeshConstPtr |
typedef pcl::ihs::MeshPtr | MeshPtr |
enum | MeshRepresentation { MR_POINTS, MR_EDGES, MR_FACES } |
How to draw the mesh. More... | |
typedef enum pcl::ihs::OpenGLViewer::MeshRepresentation | MeshRepresentation |
How to draw the mesh. | |
typedef pcl::PointXYZRGBNormal | PointXYZRGBNormal |
Public Slots | |
void | resetCamera () |
Reset the virtual camera position and orientation. | |
void | setColoring (const Coloring &coloring) |
Set the coloring mode. | |
void | setMeshRepresentation (const MeshRepresentation &representation) |
Set the mesh representation. | |
void | timerCallback () |
Requests the scene to be re-drawn (called periodically from a timer). | |
void | toggleColoring () |
Toggle the coloring mode. | |
void | toggleMeshRepresentation () |
Toggle the mesh representation. | |
Public Member Functions | |
bool | addMesh (const MeshConstPtr &mesh, const std::string &id, const Eigen::Isometry3d &T=Eigen::Isometry3d::Identity()) |
Add a mesh to be drawn. | |
bool | addMesh (const CloudXYZRGBNormalConstPtr &cloud, const std::string &id, const Eigen::Isometry3d &T=Eigen::Isometry3d::Identity()) |
Convert an organized cloud to a mesh and draw it. | |
bool | getDrawBox () const |
Check if the box is drawn. | |
virtual QSize | minimumSizeHint () const |
OpenGLViewer (QWidget *parent=0) | |
Constructor. | |
void | removeAllMeshes () |
Remove all meshes that are currently drawn. | |
bool | removeMesh (const std::string &id) |
Remove the mesh with the given id. | |
void | setBoxCoefficients (const BoxCoefficients &coeffs) |
Set the coefficients for the box. | |
void | setDrawBox (const bool enabled) |
Enable / disable drawing the box. | |
void | setPivot (const Eigen::Vector3d &pivot) |
Set the point around which the camera rotates during mouse navigation. | |
void | setPivot (const std::string &id) |
Searches the given id in the drawn meshes and calculates the pivot as the centroid of the found geometry. | |
void | setScalingFactor (const double scale) |
Set the scaling factor to convert from meters to the unit of the drawn files. | |
void | setVisibilityConfidenceNormalization (const float vis_conf_norm) |
The visibility confidence is normalized with this value (must be greater than 1). | |
virtual QSize | sizeHint () const |
void | stopTimer () |
Stop the visualization timer. | |
~OpenGLViewer () | |
Destructor. | |
Protected Member Functions | |
template<class FPS > | |
void | calcFPS (FPS &fps) const |
virtual void | paintEvent (QPaintEvent *event) |
Private Types | |
typedef pcl::ihs::CloudIHS | CloudIHS |
typedef pcl::ihs::CloudIHSConstPtr | CloudIHSConstPtr |
typedef pcl::ihs::CloudIHSPtr | CloudIHSPtr |
typedef boost::unordered_map < std::string, CloudXYZRGBNormalPtr > | CloudXYZRGBNormalMap |
typedef Eigen::Matrix < unsigned char, 3, 1 > | Color |
typedef Eigen::Matrix < unsigned char, 3, 256 > | Colormap |
typedef Eigen::Matrix < unsigned char, 3, Eigen::Dynamic > | Colors |
typedef pcl::ihs::detail::FaceVertexMesh | FaceVertexMesh |
typedef boost::shared_ptr < const FaceVertexMesh > | FaceVertexMeshConstPtr |
typedef boost::unordered_map < std::string, FaceVertexMeshPtr > | FaceVertexMeshMap |
typedef boost::shared_ptr < FaceVertexMesh > | FaceVertexMeshPtr |
typedef pcl::ihs::PointIHS | PointIHS |
Private Member Functions | |
void | calcPivot () |
Calculate the pivot for the stored id. | |
void | drawBox () |
Draw a wireframe box. | |
void | drawMeshes () |
Draw all meshes. | |
bool | getMeshIsAdded (const std::string &id) |
Check if the mesh with the given id is added. | |
void | initializeGL () |
void | mouseMoveEvent (QMouseEvent *event) |
void | mousePressEvent (QMouseEvent *event) |
void | resizeGL (int w, int h) |
void | setupViewport (const int w, const int h) |
void | wheelEvent (QWheelEvent *event) |
Private Attributes | |
BoxCoefficients | box_coefficients_ |
Coefficients of the drawn box. | |
Eigen::Vector3d | cam_pivot_ |
Center of rotation during mouse navigation. | |
std::string | cam_pivot_id_ |
Compute the pivot for the mesh with the given id. | |
Coloring | coloring_ |
How to color the shapes. | |
Colormap | colormap_ |
Colormap. | |
bool | draw_box_ |
A box is drawn if this value is true. | |
FaceVertexMeshMap | drawn_meshes_ |
Meshes stored for visualization. | |
MeshRepresentation | mesh_representation_ |
How to draw the mesh. | |
bool | mouse_pressed_begin_ |
Set to true right after the mouse got pressed and false if the mouse got moved. | |
boost::mutex | mutex_vis_ |
Synchronization. | |
Eigen::Quaterniond | R_cam_ |
Rotation of the camera. | |
double | scaling_factor_ |
Scaling factor to convert from meters to the unit of the drawn files. | |
Eigen::Vector3d | t_cam_ |
Translation of the camera. | |
boost::shared_ptr< QTimer > | timer_vis_ |
Visualization timer. | |
float | vis_conf_norm_ |
The visibility confidence is normalized with this value. | |
int | x_prev_ |
Mouse x-position of the previous mouse move event. | |
int | y_prev_ |
Mouse y-position of the previous mouse move event. |
Viewer for the in-hand scanner based on Qt and OpenGL.
Definition at line 107 of file opengl_viewer.h.
typedef pcl::ihs::CloudIHS pcl::ihs::OpenGLViewer::CloudIHS [private] |
Reimplemented in pcl::ihs::InHandScanner.
Definition at line 337 of file opengl_viewer.h.
typedef pcl::ihs::CloudIHSConstPtr pcl::ihs::OpenGLViewer::CloudIHSConstPtr [private] |
Reimplemented in pcl::ihs::InHandScanner.
Definition at line 339 of file opengl_viewer.h.
typedef pcl::ihs::CloudIHSPtr pcl::ihs::OpenGLViewer::CloudIHSPtr [private] |
Reimplemented in pcl::ihs::InHandScanner.
Definition at line 338 of file opengl_viewer.h.
Reimplemented in pcl::ihs::InHandScanner, and pcl::ihs::OfflineIntegration.
Definition at line 114 of file opengl_viewer.h.
Reimplemented in pcl::ihs::InHandScanner, and pcl::ihs::OfflineIntegration.
Definition at line 116 of file opengl_viewer.h.
typedef boost::unordered_map<std::string, CloudXYZRGBNormalPtr> pcl::ihs::OpenGLViewer::CloudXYZRGBNormalMap [private] |
Definition at line 334 of file opengl_viewer.h.
Reimplemented in pcl::ihs::InHandScanner, and pcl::ihs::OfflineIntegration.
Definition at line 115 of file opengl_viewer.h.
typedef Eigen::Matrix<unsigned char, 3, 1 > pcl::ihs::OpenGLViewer::Color [private] |
Definition at line 330 of file opengl_viewer.h.
How to color the shapes.
typedef Eigen::Matrix<unsigned char, 3, 256 > pcl::ihs::OpenGLViewer::Colormap [private] |
Definition at line 332 of file opengl_viewer.h.
typedef Eigen::Matrix<unsigned char, 3, Eigen::Dynamic> pcl::ihs::OpenGLViewer::Colors [private] |
Definition at line 331 of file opengl_viewer.h.
typedef pcl::ihs::detail::FaceVertexMesh pcl::ihs::OpenGLViewer::FaceVertexMesh [private] |
Definition at line 341 of file opengl_viewer.h.
typedef boost::shared_ptr<const FaceVertexMesh> pcl::ihs::OpenGLViewer::FaceVertexMeshConstPtr [private] |
Definition at line 343 of file opengl_viewer.h.
typedef boost::unordered_map<std::string, FaceVertexMeshPtr> pcl::ihs::OpenGLViewer::FaceVertexMeshMap [private] |
Definition at line 344 of file opengl_viewer.h.
typedef boost::shared_ptr< FaceVertexMesh> pcl::ihs::OpenGLViewer::FaceVertexMeshPtr [private] |
Definition at line 342 of file opengl_viewer.h.
Reimplemented in pcl::ihs::InHandScanner, and pcl::ihs::OfflineIntegration.
Definition at line 118 of file opengl_viewer.h.
typedef pcl::ihs::MeshConstPtr pcl::ihs::OpenGLViewer::MeshConstPtr |
Reimplemented in pcl::ihs::InHandScanner, and pcl::ihs::OfflineIntegration.
Definition at line 120 of file opengl_viewer.h.
Reimplemented in pcl::ihs::InHandScanner, and pcl::ihs::OfflineIntegration.
Definition at line 119 of file opengl_viewer.h.
How to draw the mesh.
typedef pcl::ihs::PointIHS pcl::ihs::OpenGLViewer::PointIHS [private] |
Reimplemented in pcl::ihs::InHandScanner.
Definition at line 336 of file opengl_viewer.h.
Reimplemented in pcl::ihs::InHandScanner, and pcl::ihs::OfflineIntegration.
Definition at line 113 of file opengl_viewer.h.
How to color the shapes.
COL_RGB |
Coloring according to the rgb values. |
COL_ONE_COLOR |
Use one color for all points. |
COL_VISCONF |
Coloring according to the visibility confidence. |
Definition at line 131 of file opengl_viewer.h.
How to draw the mesh.
MR_POINTS |
Draw the points. |
MR_EDGES |
Wireframe represen of the mesh. |
MR_FACES |
Draw the faces of the mesh without edges. |
Definition at line 123 of file opengl_viewer.h.
pcl::ihs::OpenGLViewer::OpenGLViewer | ( | QWidget * | parent = 0 | ) | [explicit] |
Constructor.
Definition at line 108 of file opengl_viewer.cpp.
Destructor.
Definition at line 445 of file opengl_viewer.cpp.
bool pcl::ihs::OpenGLViewer::addMesh | ( | const MeshConstPtr & | mesh, |
const std::string & | id, | ||
const Eigen::Isometry3d & | T = Eigen::Isometry3d::Identity () |
||
) |
Add a mesh to be drawn.
[in] | mesh | The input mesh. |
[in] | id | Unique identifier for the mesh. The internal mesh is replaced by the input mesh if the id already exists. |
[in] | T | Transformation applied to the mesh. Defaults to an identity transformation. |
Definition at line 453 of file opengl_viewer.cpp.
bool pcl::ihs::OpenGLViewer::addMesh | ( | const CloudXYZRGBNormalConstPtr & | cloud, |
const std::string & | id, | ||
const Eigen::Isometry3d & | T = Eigen::Isometry3d::Identity () |
||
) |
Convert an organized cloud to a mesh and draw it.
[in] | cloud | Organized input cloud. |
[in] | id | Unique identifier for the mesh. The internal mesh is replaced by the converted input mesh if the id already exists. |
[in] | T | Transformation applied to the mesh. Defaults to an identity transformation. |
Definition at line 474 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::calcFPS | ( | FPS & | fps | ) | const [inline, protected] |
Measures the performance of the current thread (selected by passing the corresponding 'fps' helper object). The resulting value is stored in the fps object.
Definition at line 308 of file opengl_viewer.h.
void pcl::ihs::OpenGLViewer::calcPivot | ( | ) | [private] |
Calculate the pivot for the stored id.
Definition at line 867 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::drawBox | ( | ) | [private] |
Draw a wireframe box.
Definition at line 979 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::drawMeshes | ( | ) | [private] |
Draw all meshes.
Definition at line 888 of file opengl_viewer.cpp.
bool pcl::ihs::OpenGLViewer::getDrawBox | ( | ) | const |
Check if the box is drawn.
Definition at line 625 of file opengl_viewer.cpp.
bool pcl::ihs::OpenGLViewer::getMeshIsAdded | ( | const std::string & | id | ) | [private] |
Check if the mesh with the given id is added.
Definition at line 858 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::initializeGL | ( | ) | [private] |
Definition at line 1039 of file opengl_viewer.cpp.
QSize pcl::ihs::OpenGLViewer::minimumSizeHint | ( | ) | const [virtual] |
Definition at line 673 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::mouseMoveEvent | ( | QMouseEvent * | event | ) | [private] |
Definition at line 1091 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::mousePressEvent | ( | QMouseEvent * | event | ) | [private] |
Definition at line 1082 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::paintEvent | ( | QPaintEvent * | event | ) | [protected, virtual] |
Reimplemented in pcl::ihs::InHandScanner, and pcl::ihs::OfflineIntegration.
Definition at line 780 of file opengl_viewer.cpp.
Remove all meshes that are currently drawn.
Definition at line 598 of file opengl_viewer.cpp.
bool pcl::ihs::OpenGLViewer::removeMesh | ( | const std::string & | id | ) |
Remove the mesh with the given id.
[in] | id | Identifier of the mesh (results in a failure if the id does not exist). |
Definition at line 585 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::resetCamera | ( | ) | [slot] |
Reset the virtual camera position and orientation.
Definition at line 706 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::resizeGL | ( | int | w, |
int | h | ||
) | [private] |
Definition at line 1074 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::setBoxCoefficients | ( | const BoxCoefficients & | coeffs | ) |
Set the coefficients for the box.
Definition at line 607 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::setColoring | ( | const Coloring & | coloring | ) | [slot] |
Set the coloring mode.
Definition at line 763 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::setDrawBox | ( | const bool | enabled | ) |
Enable / disable drawing the box.
Definition at line 616 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::setMeshRepresentation | ( | const MeshRepresentation & | representation | ) | [slot] |
Set the mesh representation.
Definition at line 731 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::setPivot | ( | const Eigen::Vector3d & | pivot | ) |
Set the point around which the camera rotates during mouse navigation.
Definition at line 633 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::setPivot | ( | const std::string & | id | ) |
Searches the given id in the drawn meshes and calculates the pivot as the centroid of the found geometry.
Definition at line 642 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::setScalingFactor | ( | const double | scale | ) |
Set the scaling factor to convert from meters to the unit of the drawn files.
Definition at line 689 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::setupViewport | ( | const int | w, |
const int | h | ||
) | [private] |
Definition at line 1046 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::setVisibilityConfidenceNormalization | ( | const float | vis_conf_norm | ) |
The visibility confidence is normalized with this value (must be greater than 1).
Definition at line 663 of file opengl_viewer.cpp.
QSize pcl::ihs::OpenGLViewer::sizeHint | ( | ) | const [virtual] |
Definition at line 681 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::stopTimer | ( | ) |
Stop the visualization timer.
Definition at line 651 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::timerCallback | ( | ) | [slot] |
Requests the scene to be re-drawn (called periodically from a timer).
Definition at line 698 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::toggleColoring | ( | ) | [slot] |
Toggle the coloring mode.
Definition at line 749 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::toggleMeshRepresentation | ( | ) | [slot] |
Toggle the mesh representation.
Definition at line 717 of file opengl_viewer.cpp.
void pcl::ihs::OpenGLViewer::wheelEvent | ( | QWheelEvent * | event | ) | [private] |
Definition at line 1144 of file opengl_viewer.cpp.
Coefficients of the drawn box.
Definition at line 419 of file opengl_viewer.h.
Eigen::Vector3d pcl::ihs::OpenGLViewer::cam_pivot_ [private] |
Center of rotation during mouse navigation.
Definition at line 431 of file opengl_viewer.h.
Compute the pivot for the mesh with the given id.
Definition at line 434 of file opengl_viewer.h.
Coloring pcl::ihs::OpenGLViewer::coloring_ [private] |
How to color the shapes.
Definition at line 413 of file opengl_viewer.h.
Colormap pcl::ihs::OpenGLViewer::colormap_ [private] |
Colormap.
Definition at line 401 of file opengl_viewer.h.
bool pcl::ihs::OpenGLViewer::draw_box_ [private] |
A box is drawn if this value is true.
Definition at line 416 of file opengl_viewer.h.
Meshes stored for visualization.
Definition at line 407 of file opengl_viewer.h.
How to draw the mesh.
Definition at line 410 of file opengl_viewer.h.
bool pcl::ihs::OpenGLViewer::mouse_pressed_begin_ [private] |
Set to true right after the mouse got pressed and false if the mouse got moved.
Definition at line 437 of file opengl_viewer.h.
boost::mutex pcl::ihs::OpenGLViewer::mutex_vis_ [private] |
Synchronization.
Definition at line 395 of file opengl_viewer.h.
Eigen::Quaterniond pcl::ihs::OpenGLViewer::R_cam_ [private] |
Rotation of the camera.
Definition at line 425 of file opengl_viewer.h.
double pcl::ihs::OpenGLViewer::scaling_factor_ [private] |
Scaling factor to convert from meters to the unit of the drawn files.
Definition at line 422 of file opengl_viewer.h.
Eigen::Vector3d pcl::ihs::OpenGLViewer::t_cam_ [private] |
Translation of the camera.
Definition at line 428 of file opengl_viewer.h.
boost::shared_ptr<QTimer> pcl::ihs::OpenGLViewer::timer_vis_ [private] |
Visualization timer.
Definition at line 398 of file opengl_viewer.h.
float pcl::ihs::OpenGLViewer::vis_conf_norm_ [private] |
The visibility confidence is normalized with this value.
Definition at line 404 of file opengl_viewer.h.
int pcl::ihs::OpenGLViewer::x_prev_ [private] |
Mouse x-position of the previous mouse move event.
Definition at line 440 of file opengl_viewer.h.
int pcl::ihs::OpenGLViewer::y_prev_ [private] |
Mouse y-position of the previous mouse move event.
Definition at line 443 of file opengl_viewer.h.