Public Slots | Signals | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
GLViewer Class Reference

OpenGL based display of the 3d model. More...

#include <glviewer.h>

List of all members.

Public Slots

void addFeatures (const std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > *feature_locations_3d)
void addPointCloud (pointcloud_type *pc, QMatrix4x4 transform)
void deleteLastNode ()
void drawToPS (QString filname)
void reset ()
void setEdges (const QList< QPair< int, int > > *edge_list)
void setRenderable (Renderable *r)
void setRotationGrid (double rot_step_in_degree)
void setStereoShift (double shift)
void setXRotation (int angle)
void setYRotation (int angle)
void setZRotation (int angle)
void toggleBackgroundColor (bool on)
void toggleFollowMode (bool on)
void toggleShowClouds (bool on)
void toggleShowEdges (bool on)
void toggleShowFeatures (bool on)
void toggleShowGrid (bool on)
void toggleShowIDs (bool on)
void toggleShowOctoMap (bool on)
void toggleShowPoses (bool on)
void toggleShowTFs (bool on)
void toggleStereo (bool on)
void toggleTriangulation ()
void updateTransforms (QList< QMatrix4x4 > *transforms)

Signals

void clickedPosition (float x, float y, float z)
void cloudRendered (pointcloud_type *)

Public Member Functions

 GLViewer (QWidget *parent=0)
QSize minimumSizeHint () const
QSize sizeHint () const
 ~GLViewer ()

Protected Member Functions

void drawAxes (float scale, float thickness=4.0)
 Draw colored axis, scale long.
void drawClouds (float xshift)
 Draw the scene. Xshift allows for a camera shift in x direction for the stereo view.
void drawEdges ()
 Draw pose graph edges in opengl.
void drawGrid ()
 Draw size x size grid into world coordinate system.
void drawNavigationAxis (int axis_idx, float scale, QString text)
void drawOneCloud (int i)
 Draw one of the clouds with the given list index.
void drawRenderable ()
void drawTriangle (const point_type &p1, const point_type &p2, const point_type &p3)
void initializeGL ()
void initialPosition ()
void makeCurrent ()
 Only switch to own context if necessary.
void mouseDoubleClickEvent (QMouseEvent *event)
void mouseMoveEvent (QMouseEvent *event)
void mousePressEvent (QMouseEvent *event)
void mouseReleaseEvent (QMouseEvent *event)
void paintGL ()
void pointCloud2GLEllipsoids (pointcloud_type *pc)
 Draw ellipsoids instead of points, that represent the depth std deviation of each point.
void pointCloud2GLPoints (pointcloud_type *pc)
 Compile the pointcloud to a GL Display List using GL_POINT.
void pointCloud2GLStrip (pointcloud_type *pc)
 Compile the pointcloud to a GL Display List using GL_TRIANGLE_STRIPs.
void pointCloud2GLTriangleList (pointcloud_type const *pc)
 Compile the pointcloud to a GL Display List using GL_TRIANGLES.
QImage renderList (QMatrix4x4 transform, int list_id)
void resizeGL (int width, int height)
void wheelEvent (QWheelEvent *event)

Protected Attributes

float bg_col_ [4]

Private Member Functions

void clearAndUpdate ()
bool setClickedPosition (int x, int y)
void setViewPoint (QMatrix4x4 cam_pose_mat)

Private Attributes

bool black_background_
bool button_pressed_
QList< GLuint > cloud_list_indices
QList< QMatrix4x4 > * cloud_matrices
QList< QPair< int, int > > edge_list_
Renderableexternal_renderable
unsigned int fast_rendering_step_
QList< GLuint > feature_list_indices
bool follow_mode_
double fov_
int height_
QPoint lastPos
QWidget * myparent
bool non_interactive_update_
GLenum polygon_mode
double rotation_stepping_
bool show_clouds_
bool show_edges_
bool show_features_
bool show_grid_
bool show_ids_
bool show_octomap_
bool show_poses_
bool show_tfs_
bool stereo_
double stereo_shift_
QMatrix4x4 viewpoint_tf_
int width_
int xRot
float xTra
int yRot
float yTra
int zRot
float zTra

Detailed Description

OpenGL based display of the 3d model.

Definition at line 28 of file glviewer.h.


Constructor & Destructor Documentation

GLViewer::GLViewer ( QWidget *  parent = 0)

Definition at line 98 of file glviewer.cpp.

Definition at line 135 of file glviewer.cpp.


Member Function Documentation

void GLViewer::addFeatures ( const std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > *  feature_locations_3d) [slot]

Definition at line 737 of file glviewer.cpp.

void GLViewer::addPointCloud ( pointcloud_type pc,
QMatrix4x4  transform 
) [slot]

Definition at line 693 of file glviewer.cpp.

void GLViewer::clearAndUpdate ( ) [inline, private]

Definition at line 1200 of file glviewer.cpp.

void GLViewer::clickedPosition ( float  x,
float  y,
float  z 
) [signal]
void GLViewer::deleteLastNode ( ) [slot]

Definition at line 908 of file glviewer.cpp.

void GLViewer::drawAxes ( float  scale,
float  thickness = 4.0 
) [protected]

Draw colored axis, scale long.

Definition at line 266 of file glviewer.cpp.

void GLViewer::drawClouds ( float  xshift) [protected]

Draw the scene. Xshift allows for a camera shift in x direction for the stereo view.

Definition at line 348 of file glviewer.cpp.

void GLViewer::drawEdges ( ) [protected]

Draw pose graph edges in opengl.

Definition at line 1065 of file glviewer.cpp.

void GLViewer::drawGrid ( ) [protected]

Draw size x size grid into world coordinate system.

Definition at line 225 of file glviewer.cpp.

void GLViewer::drawNavigationAxis ( int  axis_idx,
float  scale,
QString  text 
) [protected]

Definition at line 1234 of file glviewer.cpp.

void GLViewer::drawOneCloud ( int  i) [protected]

Draw one of the clouds with the given list index.

Definition at line 339 of file glviewer.cpp.

void GLViewer::drawRenderable ( ) [protected]

Definition at line 334 of file glviewer.cpp.

void GLViewer::drawToPS ( QString  filname) [slot]

Definition at line 1169 of file glviewer.cpp.

void GLViewer::drawTriangle ( const point_type p1,
const point_type p2,
const point_type p3 
) [inline, protected]

Draw a triangle in opengl Assumes gl mode for triangles

Definition at line 214 of file glviewer.cpp.

void GLViewer::initializeGL ( ) [protected]

Definition at line 195 of file glviewer.cpp.

void GLViewer::initialPosition ( ) [protected]

Definition at line 137 of file glviewer.cpp.

void GLViewer::makeCurrent ( ) [protected]

Only switch to own context if necessary.

Definition at line 284 of file glviewer.cpp.

QSize GLViewer::minimumSizeHint ( ) const

Definition at line 146 of file glviewer.cpp.

void GLViewer::mouseDoubleClickEvent ( QMouseEvent *  event) [protected]

Resets to certain perspectives Double clicks onto an object part will make that part the pivot of The camera movement. Depending on the button the position of the camera will be the most recent frame (left button) or the first frame (right button). If the background is clicked, the pivot will be the camera position itself

Definition at line 448 of file glviewer.cpp.

void GLViewer::mouseMoveEvent ( QMouseEvent *  event) [protected]

Definition at line 651 of file glviewer.cpp.

void GLViewer::mousePressEvent ( QMouseEvent *  event) [protected]

Definition at line 623 of file glviewer.cpp.

void GLViewer::mouseReleaseEvent ( QMouseEvent *  event) [protected]

Create context menu

Definition at line 526 of file glviewer.cpp.

void GLViewer::paintGL ( ) [protected]

Definition at line 291 of file glviewer.cpp.

Draw ellipsoids instead of points, that represent the depth std deviation of each point.

Definition at line 922 of file glviewer.cpp.

void GLViewer::pointCloud2GLPoints ( pointcloud_type pc) [protected]

Compile the pointcloud to a GL Display List using GL_POINT.

Definition at line 955 of file glviewer.cpp.

void GLViewer::pointCloud2GLStrip ( pointcloud_type pc) [protected]

Compile the pointcloud to a GL Display List using GL_TRIANGLE_STRIPs.

Definition at line 776 of file glviewer.cpp.

void GLViewer::pointCloud2GLTriangleList ( pointcloud_type const *  pc) [protected]

Compile the pointcloud to a GL Display List using GL_TRIANGLES.

Definition at line 989 of file glviewer.cpp.

QImage GLViewer::renderList ( QMatrix4x4  transform,
int  list_id 
) [protected]

Definition at line 1055 of file glviewer.cpp.

void GLViewer::reset ( ) [slot]

Definition at line 1044 of file glviewer.cpp.

void GLViewer::resizeGL ( int  width,
int  height 
) [protected]

Definition at line 427 of file glviewer.cpp.

bool GLViewer::setClickedPosition ( int  x,
int  y 
) [private]

Definition at line 1127 of file glviewer.cpp.

void GLViewer::setEdges ( const QList< QPair< int, int > > *  edge_list) [slot]

Definition at line 1059 of file glviewer.cpp.

void GLViewer::setRenderable ( Renderable r) [slot]

Definition at line 1249 of file glviewer.cpp.

void GLViewer::setRotationGrid ( double  rot_step_in_degree) [slot]

Definition at line 186 of file glviewer.cpp.

void GLViewer::setStereoShift ( double  shift) [slot]

Definition at line 190 of file glviewer.cpp.

void GLViewer::setViewPoint ( QMatrix4x4  cam_pose_mat) [private]

cam_pose_mat transforms the viewpoint from the origin cam_pose_mat is inverted, i.e. it should describes the transformation of the camera itself

Moving the camera is inverse to moving the points to draw

Definition at line 1122 of file glviewer.cpp.

void GLViewer::setXRotation ( int  angle) [slot]

Definition at line 161 of file glviewer.cpp.

void GLViewer::setYRotation ( int  angle) [slot]

Definition at line 170 of file glviewer.cpp.

void GLViewer::setZRotation ( int  angle) [slot]

Definition at line 178 of file glviewer.cpp.

QSize GLViewer::sizeHint ( ) const

Definition at line 150 of file glviewer.cpp.

void GLViewer::toggleBackgroundColor ( bool  on) [slot]

Definition at line 478 of file glviewer.cpp.

void GLViewer::toggleFollowMode ( bool  on) [slot]

Definition at line 521 of file glviewer.cpp.

void GLViewer::toggleShowClouds ( bool  on) [slot]

Definition at line 497 of file glviewer.cpp.

void GLViewer::toggleShowEdges ( bool  on) [slot]

Definition at line 513 of file glviewer.cpp.

void GLViewer::toggleShowFeatures ( bool  on) [slot]

Definition at line 489 of file glviewer.cpp.

void GLViewer::toggleShowGrid ( bool  on) [slot]

Definition at line 505 of file glviewer.cpp.

void GLViewer::toggleShowIDs ( bool  on) [slot]

Definition at line 509 of file glviewer.cpp.

void GLViewer::toggleShowOctoMap ( bool  on) [slot]

Definition at line 493 of file glviewer.cpp.

void GLViewer::toggleShowPoses ( bool  on) [slot]

Definition at line 517 of file glviewer.cpp.

void GLViewer::toggleShowTFs ( bool  on) [slot]

Definition at line 501 of file glviewer.cpp.

void GLViewer::toggleStereo ( bool  on) [slot]

Definition at line 473 of file glviewer.cpp.

Definition at line 1155 of file glviewer.cpp.

void GLViewer::updateTransforms ( QList< QMatrix4x4 > *  transforms) [slot]

Definition at line 681 of file glviewer.cpp.

void GLViewer::wheelEvent ( QWheelEvent *  event) [protected]

Definition at line 628 of file glviewer.cpp.


Member Data Documentation

float GLViewer::bg_col_[4] [protected]

Definition at line 110 of file glviewer.h.

Definition at line 145 of file glviewer.h.

bool GLViewer::button_pressed_ [private]

Definition at line 150 of file glviewer.h.

QList<GLuint> GLViewer::cloud_list_indices [private]

Definition at line 124 of file glviewer.h.

QList<QMatrix4x4>* GLViewer::cloud_matrices [private]

Definition at line 127 of file glviewer.h.

QList<QPair<int, int> > GLViewer::edge_list_ [private]

Definition at line 126 of file glviewer.h.

Definition at line 153 of file glviewer.h.

unsigned int GLViewer::fast_rendering_step_ [private]

Definition at line 152 of file glviewer.h.

QList<GLuint> GLViewer::feature_list_indices [private]

Definition at line 125 of file glviewer.h.

bool GLViewer::follow_mode_ [private]

Definition at line 143 of file glviewer.h.

double GLViewer::fov_ [private]

Definition at line 147 of file glviewer.h.

int GLViewer::height_ [private]

Definition at line 146 of file glviewer.h.

QPoint GLViewer::lastPos [private]

Definition at line 122 of file glviewer.h.

QWidget* GLViewer::myparent [private]

Definition at line 149 of file glviewer.h.

Definition at line 151 of file glviewer.h.

GLenum GLViewer::polygon_mode [private]

Definition at line 123 of file glviewer.h.

double GLViewer::rotation_stepping_ [private]

Definition at line 148 of file glviewer.h.

bool GLViewer::show_clouds_ [private]

Definition at line 140 of file glviewer.h.

bool GLViewer::show_edges_ [private]

Definition at line 139 of file glviewer.h.

bool GLViewer::show_features_ [private]

Definition at line 142 of file glviewer.h.

bool GLViewer::show_grid_ [private]

Definition at line 137 of file glviewer.h.

bool GLViewer::show_ids_ [private]

Definition at line 136 of file glviewer.h.

bool GLViewer::show_octomap_ [private]

Definition at line 141 of file glviewer.h.

bool GLViewer::show_poses_ [private]

Definition at line 135 of file glviewer.h.

bool GLViewer::show_tfs_ [private]

Definition at line 138 of file glviewer.h.

bool GLViewer::stereo_ [private]

Definition at line 144 of file glviewer.h.

double GLViewer::stereo_shift_ [private]

Definition at line 147 of file glviewer.h.

QMatrix4x4 GLViewer::viewpoint_tf_ [private]

Definition at line 128 of file glviewer.h.

int GLViewer::width_ [private]

Definition at line 146 of file glviewer.h.

int GLViewer::xRot [private]

Definition at line 120 of file glviewer.h.

float GLViewer::xTra [private]

Definition at line 121 of file glviewer.h.

int GLViewer::yRot [private]

Definition at line 120 of file glviewer.h.

float GLViewer::yTra [private]

Definition at line 121 of file glviewer.h.

int GLViewer::zRot [private]

Definition at line 120 of file glviewer.h.

float GLViewer::zTra [private]

Definition at line 121 of file glviewer.h.


The documentation for this class was generated from the following files:


rgbdslam_v2
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Thu Jun 6 2019 21:49:45