#include <height_map_2d.h>
Public Types | |
| typedef pcl::PointCloud< PointT > | PointCloud |
| typedef boost::shared_ptr < const PointCloud > | PointCloudConstPtr |
| typedef boost::shared_ptr < PointCloud > | PointCloudPtr |
Public Member Functions | |
| void | compute (pcl::people::PersonCluster< PointT > &cluster) |
| Compute the height map with the projection of cluster points onto the ground plane. | |
| void | filterMaxima () |
| Filter maxima of the height map by imposing a minimum distance between them. | |
| float | getBinSize () |
| Get bin size for the height map. | |
| std::vector< int > & | getHeightMap () |
| Get the height map as a vector of int. | |
| std::vector< int > & | getMaximaCloudIndicesFiltered () |
| Return the point cloud indices corresponding to the maxima computed after the filterMaxima method. | |
| int & | getMaximaNumberAfterFiltering () |
| Return the maxima number after the filterMaxima method. | |
| float | getMinimumDistanceBetweenMaxima () |
| Get minimum distance between maxima of the height map. | |
| HeightMap2D () | |
| Constructor. | |
| void | searchLocalMaxima () |
| Compute local maxima of the height map. | |
| void | setBinSize (float bin_size) |
| Set bin size for the height map. | |
| void | setGround (Eigen::VectorXf &ground_coeffs) |
| Set the ground coefficients. | |
| void | setInputCloud (PointCloudPtr &cloud) |
| Set initial cluster indices. | |
| void | setMinimumDistanceBetweenMaxima (float minimum_distance_between_maxima) |
| Set minimum distance between maxima. | |
| void | setSensorPortraitOrientation (bool vertical) |
| Set sensor orientation to landscape mode (false) or portrait mode (true). | |
| virtual | ~HeightMap2D () |
| Destructor. | |
Protected Attributes | |
| float | bin_size_ |
| bin dimension | |
| std::vector< int > | buckets_ |
| vector with maximum height values for every bin (height map) | |
| std::vector< int > | buckets_cloud_indices_ |
| indices of the pointcloud points with maximum height for every bin | |
| PointCloudPtr | cloud_ |
| pointer to the input cloud | |
| Eigen::VectorXf | ground_coeffs_ |
| ground plane coefficients | |
| std::vector< int > | maxima_cloud_indices_ |
| contains the point cloud position of the maxima (indices of the point cloud) | |
| std::vector< int > | maxima_cloud_indices_filtered_ |
| contains the point cloud position of the maxima after filtering | |
| std::vector< int > | maxima_indices_ |
| contains the position of the maxima in the buckets vector | |
| std::vector< int > | maxima_indices_filtered_ |
| contains the position of the maxima in the buckets array after filtering | |
| int | maxima_number_ |
| number of local maxima in the height map | |
| int | maxima_number_after_filtering_ |
| number of local maxima after filtering | |
| float | min_dist_between_maxima_ |
| minimum allowed distance between maxima | |
| float | sqrt_ground_coeffs_ |
| ground plane normalization factor | |
| bool | vertical_ |
| if true, the sensor is considered to be vertically placed (portrait mode) | |
Definition at line 58 of file height_map_2d.h.
| typedef pcl::PointCloud<PointT> pcl::people::HeightMap2D< PointT >::PointCloud |
Definition at line 62 of file height_map_2d.h.
| typedef boost::shared_ptr<const PointCloud> pcl::people::HeightMap2D< PointT >::PointCloudConstPtr |
Definition at line 64 of file height_map_2d.h.
| typedef boost::shared_ptr<PointCloud> pcl::people::HeightMap2D< PointT >::PointCloudPtr |
Definition at line 63 of file height_map_2d.h.
| pcl::people::HeightMap2D< PointT >::HeightMap2D | ( | ) |
Constructor.
Definition at line 47 of file height_map_2d.hpp.
| pcl::people::HeightMap2D< PointT >::~HeightMap2D | ( | ) | [virtual] |
Destructor.
Definition at line 309 of file height_map_2d.hpp.
| void pcl::people::HeightMap2D< PointT >::compute | ( | pcl::people::PersonCluster< PointT > & | cluster | ) |
Compute the height map with the projection of cluster points onto the ground plane.
| [in] | cluster | The PersonCluster used to compute the height map. |
Definition at line 59 of file height_map_2d.hpp.
| void pcl::people::HeightMap2D< PointT >::filterMaxima | ( | ) |
Filter maxima of the height map by imposing a minimum distance between them.
Definition at line 203 of file height_map_2d.hpp.
| float pcl::people::HeightMap2D< PointT >::getBinSize | ( | ) |
Get bin size for the height map.
Definition at line 285 of file height_map_2d.hpp.
| std::vector< int > & pcl::people::HeightMap2D< PointT >::getHeightMap | ( | ) |
Get the height map as a vector of int.
Definition at line 279 of file height_map_2d.hpp.
| std::vector< int > & pcl::people::HeightMap2D< PointT >::getMaximaCloudIndicesFiltered | ( | ) |
Return the point cloud indices corresponding to the maxima computed after the filterMaxima method.
Definition at line 303 of file height_map_2d.hpp.
| int & pcl::people::HeightMap2D< PointT >::getMaximaNumberAfterFiltering | ( | ) |
Return the maxima number after the filterMaxima method.
Definition at line 297 of file height_map_2d.hpp.
| float pcl::people::HeightMap2D< PointT >::getMinimumDistanceBetweenMaxima | ( | ) |
Get minimum distance between maxima of the height map.
Definition at line 291 of file height_map_2d.hpp.
| void pcl::people::HeightMap2D< PointT >::searchLocalMaxima | ( | ) |
Compute local maxima of the height map.
Definition at line 119 of file height_map_2d.hpp.
| void pcl::people::HeightMap2D< PointT >::setBinSize | ( | float | bin_size | ) |
Set bin size for the height map.
| [in] | bin_size | Bin size for the height map (default = 0.06). |
Definition at line 261 of file height_map_2d.hpp.
| void pcl::people::HeightMap2D< PointT >::setGround | ( | Eigen::VectorXf & | ground_coeffs | ) |
Set the ground coefficients.
| [in] | ground_coeffs | The ground plane coefficients. |
Definition at line 254 of file height_map_2d.hpp.
| void pcl::people::HeightMap2D< PointT >::setInputCloud | ( | PointCloudPtr & | cloud | ) |
Set initial cluster indices.
| [in] | cloud | A pointer to the input cloud. |
Definition at line 248 of file height_map_2d.hpp.
| void pcl::people::HeightMap2D< PointT >::setMinimumDistanceBetweenMaxima | ( | float | minimum_distance_between_maxima | ) |
Set minimum distance between maxima.
| [in] | minimum_distance_between_maxima | Minimum allowed distance between maxima (default = 0.3). |
Definition at line 267 of file height_map_2d.hpp.
| void pcl::people::HeightMap2D< PointT >::setSensorPortraitOrientation | ( | bool | vertical | ) |
Set sensor orientation to landscape mode (false) or portrait mode (true).
| [in] | vertical | Landscape (false) or portrait (true) mode (default = false). |
Definition at line 273 of file height_map_2d.hpp.
float pcl::people::HeightMap2D< PointT >::bin_size_ [protected] |
bin dimension
Definition at line 182 of file height_map_2d.h.
std::vector<int> pcl::people::HeightMap2D< PointT >::buckets_ [protected] |
vector with maximum height values for every bin (height map)
Definition at line 176 of file height_map_2d.h.
std::vector<int> pcl::people::HeightMap2D< PointT >::buckets_cloud_indices_ [protected] |
indices of the pointcloud points with maximum height for every bin
Definition at line 179 of file height_map_2d.h.
PointCloudPtr pcl::people::HeightMap2D< PointT >::cloud_ [protected] |
pointer to the input cloud
Definition at line 170 of file height_map_2d.h.
Eigen::VectorXf pcl::people::HeightMap2D< PointT >::ground_coeffs_ [protected] |
ground plane coefficients
Definition at line 164 of file height_map_2d.h.
std::vector<int> pcl::people::HeightMap2D< PointT >::maxima_cloud_indices_ [protected] |
contains the point cloud position of the maxima (indices of the point cloud)
Definition at line 191 of file height_map_2d.h.
std::vector<int> pcl::people::HeightMap2D< PointT >::maxima_cloud_indices_filtered_ [protected] |
contains the point cloud position of the maxima after filtering
Definition at line 200 of file height_map_2d.h.
std::vector<int> pcl::people::HeightMap2D< PointT >::maxima_indices_ [protected] |
contains the position of the maxima in the buckets vector
Definition at line 188 of file height_map_2d.h.
std::vector<int> pcl::people::HeightMap2D< PointT >::maxima_indices_filtered_ [protected] |
contains the position of the maxima in the buckets array after filtering
Definition at line 197 of file height_map_2d.h.
int pcl::people::HeightMap2D< PointT >::maxima_number_ [protected] |
number of local maxima in the height map
Definition at line 185 of file height_map_2d.h.
int pcl::people::HeightMap2D< PointT >::maxima_number_after_filtering_ [protected] |
number of local maxima after filtering
Definition at line 194 of file height_map_2d.h.
float pcl::people::HeightMap2D< PointT >::min_dist_between_maxima_ [protected] |
minimum allowed distance between maxima
Definition at line 203 of file height_map_2d.h.
float pcl::people::HeightMap2D< PointT >::sqrt_ground_coeffs_ [protected] |
ground plane normalization factor
Definition at line 167 of file height_map_2d.h.
bool pcl::people::HeightMap2D< PointT >::vertical_ [protected] |
if true, the sensor is considered to be vertically placed (portrait mode)
Definition at line 173 of file height_map_2d.h.