PCL histogram visualizer main class. More...
#include <histogram_visualizer.h>
Classes | |
struct | ExitCallback |
struct | ExitMainLoopTimerCallback |
Public Member Functions | |
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, from a cloud containing a single histogram. | |
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 from a cloud containing a single histogram. | |
template<typename PointT > | |
bool | addFeatureHistogram (const pcl::PointCloud< PointT > &cloud, const std::string &field_name, const int index, const std::string &id="cloud", int win_width=640, int win_height=200) |
Add a histogram feature to screen as a separate window. | |
bool | addFeatureHistogram (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name, const int index, 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 | 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) |
Spin once method. Calls the interactor and updates the screen once. | |
template<typename PointT > | |
bool | updateFeatureHistogram (const pcl::PointCloud< PointT > &cloud, int hsize, const std::string &id="cloud") |
Update a histogram feature that is already on screen, with a cloud containing a single histogram. | |
bool | updateFeatureHistogram (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name, const std::string &id="cloud") |
Update a histogram feature that is already on screen, with a cloud containing a single histogram. | |
template<typename PointT > | |
bool | updateFeatureHistogram (const pcl::PointCloud< PointT > &cloud, const std::string &field_name, const int index, const std::string &id="cloud") |
Update a histogram feature that is already on screen, with a cloud containing a single histogram. | |
bool | updateFeatureHistogram (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name, const int index, const std::string &id="cloud") |
Update a histogram feature that is already on screen, with a cloud containing a single histogram. | |
void | updateWindowPositions () |
Update all window positions on screen so that they fit. | |
virtual | ~PCLHistogramVisualizer () |
Protected Member Functions | |
void | createActor (const vtkSmartPointer< vtkDoubleArray > &xy_array, RenWinInteract &renwinint, const std::string &id, const int win_width, const int win_height) |
Create a 2D actor from the given vtkDoubleArray histogram and add it to the screen. | |
void | reCreateActor (const vtkSmartPointer< vtkDoubleArray > &xy_array, RenWinInteract *renwinupd, const int hsize) |
Remove the current 2d actor and create a new 2D actor from the given vtkDoubleArray histogram and add it to the screen. | |
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. | |
bool | stopped_ |
Set to true when the histogram visualizer is ready to be terminated. | |
RenWinInteractMap | wins_ |
A map of all windows on screen (with their renderers and interactors). |
PCL histogram visualizer main class.
Definition at line 55 of file histogram_visualizer.h.
PCL histogram visualizer constructor.
Definition at line 49 of file histogram_visualizer.cpp.
virtual pcl::visualization::PCLHistogramVisualizer::~PCLHistogramVisualizer | ( | ) | [inline, virtual] |
Definition at line 61 of file histogram_visualizer.h.
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 |
||
) |
Add a histogram feature to screen as a separate window, from a cloud containing a single histogram.
[in] | cloud | the PointCloud dataset containing the histogram |
[in] | hsize | the length of the histogram |
[in] | id | the point cloud object id (default: cloud) |
[in] | win_width | the width of the window |
[in] | win_height | the height of the window |
Definition at line 45 of file histogram_visualizer.hpp.
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 from a cloud containing a single histogram.
[in] | cloud | the PointCloud dataset containing the histogram |
[in] | field_name | the field name containing the histogram |
[in] | id | the point cloud object id (default: cloud) |
[in] | win_width | the width of the window |
[in] | win_height | the height of the window |
Definition at line 358 of file histogram_visualizer.cpp.
bool pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram | ( | const pcl::PointCloud< PointT > & | cloud, |
const std::string & | field_name, | ||
const int | index, | ||
const std::string & | id = "cloud" , |
||
int | win_width = 640 , |
||
int | win_height = 200 |
||
) |
Add a histogram feature to screen as a separate window.
[in] | cloud | the PointCloud dataset containing the histogram |
[in] | field_name | the field name containing the histogram |
[in] | index | the point index to extract the histogram from |
[in] | id | the point cloud object id (default: cloud) |
[in] | win_width | the width of the window |
[in] | win_height | the height of the window |
Definition at line 81 of file histogram_visualizer.hpp.
bool pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram | ( | const sensor_msgs::PointCloud2 & | cloud, |
const std::string & | field_name, | ||
const int | index, | ||
const std::string & | id = "cloud" , |
||
int | win_width = 640 , |
||
int | win_height = 200 |
||
) |
Add a histogram feature to screen as a separate window.
[in] | cloud | the PointCloud dataset containing the histogram |
[in] | field_name | the field name containing the histogram |
[in] | index | the point index to extract the histogram from |
[in] | id | the point cloud object id (default: cloud) |
[in] | win_width | the width of the window |
[in] | win_height | the height of the window |
Definition at line 405 of file histogram_visualizer.cpp.
void pcl::visualization::PCLHistogramVisualizer::createActor | ( | const vtkSmartPointer< vtkDoubleArray > & | xy_array, |
RenWinInteract & | renwinint, | ||
const std::string & | id, | ||
const int | win_width, | ||
const int | win_height | ||
) | [protected] |
Create a 2D actor from the given vtkDoubleArray histogram and add it to the screen.
[in] | xy_array | the input vtkDoubleArray holding the histogram data |
[out] | renwinint | the resultant render window interactor holding the rendered object |
[in] | id | the point cloud object id |
[in] | win_width | the width of the window |
[in] | win_height | the height of the window |
Definition at line 271 of file histogram_visualizer.cpp.
void pcl::visualization::PCLHistogramVisualizer::reCreateActor | ( | const vtkSmartPointer< vtkDoubleArray > & | xy_array, |
RenWinInteract * | renwinupd, | ||
const int | hsize | ||
) | [protected] |
Remove the current 2d actor and create a new 2D actor from the given vtkDoubleArray histogram and add it to the screen.
[in] | xy_array | the input vtkDoubleArray holding the histogram data |
[out] | renwinint | the resultant render window interactor holding the rendered object |
[in] | id | the point cloud object id |
Definition at line 244 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.
[in] | r | the red component of the RGB color |
[in] | g | the green component of the RGB color |
[in] | b | the blue component of the RGB color |
[in] | viewport | the view port (default: all) |
Definition at line 180 of file histogram_visualizer.cpp.
void pcl::visualization::PCLHistogramVisualizer::setGlobalYRange | ( | float | minp, |
float | maxp | ||
) |
Set the Y range to minp-maxp for all histograms.
[in] | minp | the minimum Y range |
[in] | maxp | the maximum Y range |
Definition at line 204 of file histogram_visualizer.cpp.
Spin method. Calls the interactor and runs an internal loop.
Definition at line 164 of file histogram_visualizer.cpp.
void pcl::visualization::PCLHistogramVisualizer::spinOnce | ( | int | time = 1 | ) |
Spin once method. Calls the interactor and updates the screen once.
[in] | time | - How long (in ms) should the visualization loop be allowed to run. |
Definition at line 105 of file histogram_visualizer.cpp.
bool pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram | ( | const pcl::PointCloud< PointT > & | cloud, |
int | hsize, | ||
const std::string & | id = "cloud" |
||
) |
Update a histogram feature that is already on screen, with a cloud containing a single histogram.
[in] | cloud | the PointCloud dataset containing the histogram |
[in] | hsize | the length of the histogram |
[in] | id | the point cloud object id (default: cloud) |
Definition at line 138 of file histogram_visualizer.hpp.
bool pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram | ( | const sensor_msgs::PointCloud2 & | cloud, |
const std::string & | field_name, | ||
const std::string & | id = "cloud" |
||
) |
Update a histogram feature that is already on screen, with a cloud containing a single histogram.
[in] | cloud | the PointCloud dataset containing the histogram |
[in] | field_name | the field name containing the histogram |
[in] | id | the point cloud object id (default: cloud) |
Definition at line 465 of file histogram_visualizer.cpp.
bool pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram | ( | const pcl::PointCloud< PointT > & | cloud, |
const std::string & | field_name, | ||
const int | index, | ||
const std::string & | id = "cloud" |
||
) |
Update a histogram feature that is already on screen, with a cloud containing a single histogram.
[in] | cloud | the PointCloud dataset containing the histogram |
[in] | field_name | the field name containing the histogram |
[in] | index | the point index to extract the histogram from |
[in] | id | the point cloud object id (default: cloud) |
Definition at line 168 of file histogram_visualizer.hpp.
bool pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram | ( | const sensor_msgs::PointCloud2 & | cloud, |
const std::string & | field_name, | ||
const int | index, | ||
const std::string & | id = "cloud" |
||
) |
Update a histogram feature that is already on screen, with a cloud containing a single histogram.
[in] | cloud | the PointCloud dataset containing the histogram |
[in] | field_name | the field name containing the histogram |
[in] | index | the point index to extract the histogram from |
[in] | id | the point cloud object id (default: cloud) |
Definition at line 504 of file histogram_visualizer.cpp.
Update all window positions on screen so that they fit.
Definition at line 215 of file histogram_visualizer.cpp.
vtkSmartPointer<ExitCallback> pcl::visualization::PCLHistogramVisualizer::exit_callback_ [private] |
Definition at line 278 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 277 of file histogram_visualizer.h.
bool pcl::visualization::PCLHistogramVisualizer::stopped_ [private] |
Set to true when the histogram visualizer is ready to be terminated.
Definition at line 280 of file histogram_visualizer.h.
A map of all windows on screen (with their renderers and interactors).
Definition at line 224 of file histogram_visualizer.h.