pcl_visualization::PCLHistogramVisualizer Class Reference

PCL histogram visualizer main class. More...

#include <histogram_visualizer.h>

List of all members.

Classes

struct  ExitCallback
struct  ExitMainLoopTimerCallback

Public Member Functions

bool addFeatureHistogram (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name, const std::string &id="cloud", int win_width=640, int win_height=200)
 Add a histogram feature to screen as a separate window.
template<typename PointT >
bool addFeatureHistogram (const pcl::PointCloud< PointT > &cloud, int hsize, const std::string &id="cloud", int win_width=640, int win_height=200)
 Add a histogram feature to screen as a separate window.
 PCLHistogramVisualizer ()
 PCL histogram visualizer constructor.
void resetStoppedFlag ()
 Set the stopped flag back to false.
void setBackgroundColor (const double &r, const double &g, const double &b, int viewport=0)
 Set the viewport's background color.
void setGlobalYRange (float minp, float maxp)
 Set the Y range to minp-maxp for all histograms.
void spin ()
 Spin method. Calls the interactor and runs an internal loop.
void spinOnce (int time=1, bool force_redraw=false)
 Spin once method. Calls the interactor and updates the screen once.
void updateWindowPositions ()
 Update all window positions on screen so that they fit.
bool wasStopped ()
 Returns true when the user tried to close the window.

Private Attributes

vtkSmartPointer< ExitCallbackexit_callback_
vtkSmartPointer
< ExitMainLoopTimerCallback
exit_main_loop_timer_callback_
 Callback object enabling us to leave the main loop, when a timer fires.
RenWinInteractMap wins_
 A map of all windows on screen (with their renderers and interactors).

Detailed Description

PCL histogram visualizer main class.

Author:
Radu Bogdan Rusu

Definition at line 55 of file histogram_visualizer.h.


Constructor & Destructor Documentation

pcl_visualization::PCLHistogramVisualizer::PCLHistogramVisualizer (  ) 

PCL histogram visualizer constructor.

Definition at line 44 of file histogram_visualizer.cpp.


Member Function Documentation

bool pcl_visualization::PCLHistogramVisualizer::addFeatureHistogram ( const sensor_msgs::PointCloud2 &  cloud,
const std::string &  field_name,
const std::string &  id = "cloud",
int  win_width = 640,
int  win_height = 200 
)

Add a histogram feature to screen as a separate window.

Parameters:
cloud the PointCloud dataset containing the histogram
field_name the field name containing the histogram
id the point cloud object id (default: cloud)
win_width the size of the window (width)
win_height the size of the window (width)

Definition at line 228 of file histogram_visualizer.cpp.

template<typename PointT >
bool pcl_visualization::PCLHistogramVisualizer::addFeatureHistogram ( const pcl::PointCloud< PointT > &  cloud,
int  hsize,
const std::string &  id = "cloud",
int  win_width = 640,
int  win_height = 200 
) [inline]

Add a histogram feature to screen as a separate window.

Parameters:
cloud the PointCloud dataset containing the histogram
hsize the length of the histogram
id the point cloud object id (default: cloud)
win_width the size of the window (width)
win_height the size of the window (width)

Definition at line 40 of file histogram_visualizer.hpp.

void pcl_visualization::PCLHistogramVisualizer::resetStoppedFlag (  ) 

Set the stopped flag back to false.

Definition at line 156 of file histogram_visualizer.cpp.

void pcl_visualization::PCLHistogramVisualizer::setBackgroundColor ( const double &  r,
const double &  g,
const double &  b,
int  viewport = 0 
)

Set the viewport's background color.

Parameters:
r the red component of the RGB color
g the green component of the RGB color
b the blue component of the RGB color
viewport the view port (default: all)

Definition at line 164 of file histogram_visualizer.cpp.

void pcl_visualization::PCLHistogramVisualizer::setGlobalYRange ( float  minp,
float  maxp 
)

Set the Y range to minp-maxp for all histograms.

Parameters:
minp the minimum Y range
maxp the maximum Y range

Definition at line 188 of file histogram_visualizer.cpp.

void pcl_visualization::PCLHistogramVisualizer::spin (  ) 

Spin method. Calls the interactor and runs an internal loop.

Definition at line 121 of file histogram_visualizer.cpp.

void pcl_visualization::PCLHistogramVisualizer::spinOnce ( int  time = 1,
bool  force_redraw = false 
)

Spin once method. Calls the interactor and updates the screen once.

Parameters:
time - How long (in ms) should the visualization loop be allowed to run.
force_redraw - if false it might return without doing anything if the interactor's framerate does not require a redraw yet.

Definition at line 80 of file histogram_visualizer.cpp.

void pcl_visualization::PCLHistogramVisualizer::updateWindowPositions (  ) 

Update all window positions on screen so that they fit.

Definition at line 199 of file histogram_visualizer.cpp.

bool pcl_visualization::PCLHistogramVisualizer::wasStopped (  ) 

Returns true when the user tried to close the window.

Definition at line 143 of file histogram_visualizer.cpp.


Member Data Documentation

Definition at line 148 of file histogram_visualizer.h.

Callback object enabling us to leave the main loop, when a timer fires.

Definition at line 147 of file histogram_visualizer.h.

A map of all windows on screen (with their renderers and interactors).

Definition at line 107 of file histogram_visualizer.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


pcl_visualization
Author(s): Radu Bogdan Rusu, Bastian Steder, Ethan Rublee
autogenerated on Fri Jan 11 09:59:19 2013