$search
PCL histogram visualizer main class. More...
#include <histogram_visualizer.h>
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< ExitCallback > | exit_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). |
PCL histogram visualizer main class.
Definition at line 57 of file histogram_visualizer.h.
pcl_visualization::PCLHistogramVisualizer::PCLHistogramVisualizer | ( | ) |
PCL histogram visualizer constructor.
Definition at line 44 of file histogram_visualizer.cpp.
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.
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.
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.
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.
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.
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.
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.
vtkSmartPointer<ExitCallback> pcl_visualization::PCLHistogramVisualizer::exit_callback_ [private] |
Definition at line 156 of file histogram_visualizer.h.
vtkSmartPointer<ExitMainLoopTimerCallback> pcl_visualization::PCLHistogramVisualizer::exit_main_loop_timer_callback_ [private] |
Callback object enabling us to leave the main loop, when a timer fires.
Definition at line 155 of file histogram_visualizer.h.
A map of all windows on screen (with their renderers and interactors).
Definition at line 115 of file histogram_visualizer.h.