#include <person_cluster.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 | drawTBoundingBox (pcl::visualization::PCLVisualizer &viewer, int person_number) |
Draws the theoretical 3D bounding box of the cluster in the PCL visualizer. | |
float | getAngle () |
Returns the angle formed by the cluster's centroid with respect to the sensor (in radians). | |
float | getAngleMax () |
Returns the maximum angle formed by the cluster with respect to the sensor (in radians). | |
float | getAngleMin () |
Returns the minimum angle formed by the cluster with respect to the sensor (in radians). | |
Eigen::Vector3f & | getBottom () |
Returns the bottom point. | |
Eigen::Vector3f & | getCenter () |
Returns the centroid. | |
float | getDistance () |
Returns the distance of the cluster from the sensor. | |
float | getHeight () |
Returns the height of the cluster. | |
pcl::PointIndices & | getIndices () |
Returns the indices of the point cloud points corresponding to the cluster. | |
Eigen::Vector3f & | getMax () |
Returns the point formed by max x, max y and max z. | |
Eigen::Vector3f & | getMin () |
Returns the point formed by min x, min y and min z. | |
int | getNumberPoints () |
Returns the number of points of the cluster. | |
float | getPersonConfidence () |
Returns the HOG confidence. | |
Eigen::Vector3f & | getTBottom () |
Returns the theoretical bottom point. | |
Eigen::Vector3f & | getTCenter () |
Returns the theoretical centroid (at half height). | |
Eigen::Vector3f & | getTop () |
Returns the top point. | |
Eigen::Vector3f & | getTTop () |
Returns the theoretical top point. | |
PersonCluster (const PointCloudPtr &input_cloud, const pcl::PointIndices &indices, const Eigen::VectorXf &ground_coeffs, float sqrt_ground_coeffs, bool head_centroid, bool vertical=false) | |
Constructor. | |
void | setHeight (float height) |
Sets the cluster height. | |
void | setPersonConfidence (float confidence) |
Sets the HOG confidence. | |
float | updateHeight (const Eigen::VectorXf &ground_coeffs) |
Update the height of the cluster. | |
float | updateHeight (const Eigen::VectorXf &ground_coeffs, float sqrt_ground_coeffs) |
Update the height of the cluster. | |
virtual | ~PersonCluster () |
Destructor. | |
Protected Member Functions | |
void | init (const PointCloudPtr &input_cloud, const pcl::PointIndices &indices, const Eigen::VectorXf &ground_coeffs, float sqrt_ground_coeffs, bool head_centroid, bool vertical) |
PersonCluster initialization. | |
Protected Attributes | |
float | angle_ |
Cluster centroid horizontal angle with respect to z axis. | |
float | angle_max_ |
Maximum angle of the cluster points. | |
float | angle_min_ |
Minimum angle of the cluster points. | |
Eigen::Vector3f | bottom_ |
Cluster bottom point. | |
float | c_x_ |
x coordinate of the cluster centroid. | |
float | c_y_ |
y coordinate of the cluster centroid. | |
float | c_z_ |
z coordinate of the cluster centroid. | |
Eigen::Vector3f | center_ |
Cluster centroid. | |
float | distance_ |
Cluster distance from the sensor. | |
bool | head_centroid_ |
float | height_ |
Cluster height from the ground plane. | |
Eigen::Vector3f | max_ |
Vector containing the maximum coordinates of the cluster. | |
float | max_x_ |
Maximum x coordinate of the cluster points. | |
float | max_y_ |
Maximum y coordinate of the cluster points. | |
float | max_z_ |
Maximum z coordinate of the cluster points. | |
Eigen::Vector3f | min_ |
Vector containing the minimum coordinates of the cluster. | |
float | min_x_ |
Minimum x coordinate of the cluster points. | |
float | min_y_ |
Minimum y coordinate of the cluster points. | |
float | min_z_ |
Minimum z coordinate of the cluster points. | |
int | n_ |
Number of cluster points. | |
float | person_confidence_ |
PersonCluster HOG confidence. | |
pcl::PointIndices | points_indices_ |
Point cloud indices of the cluster points. | |
float | sum_x_ |
Sum of x coordinates of the cluster points. | |
float | sum_y_ |
Sum of y coordinates of the cluster points. | |
float | sum_z_ |
Sum of z coordinates of the cluster points. | |
Eigen::Vector3f | tbottom_ |
Theoretical cluster bottom (lying on the ground plane). | |
Eigen::Vector3f | tcenter_ |
Theoretical cluster center (between ttop_ and tbottom_). | |
Eigen::Vector3f | top_ |
Cluster top point. | |
Eigen::Vector3f | ttop_ |
Theoretical cluster top. | |
bool | vertical_ |
If true, the sensor is considered to be vertically placed (portrait mode). | |
Friends | |
bool | operator< (const PersonCluster< PointT > &c1, const PersonCluster< PointT > &c2) |
For sorting purpose: sort by distance. |
Definition at line 59 of file person_cluster.h.
typedef pcl::PointCloud<PointT> pcl::people::PersonCluster< PointT >::PointCloud |
Definition at line 138 of file person_cluster.h.
typedef boost::shared_ptr<const PointCloud> pcl::people::PersonCluster< PointT >::PointCloudConstPtr |
Definition at line 140 of file person_cluster.h.
typedef boost::shared_ptr<PointCloud> pcl::people::PersonCluster< PointT >::PointCloudPtr |
Definition at line 139 of file person_cluster.h.
pcl::people::PersonCluster< PointT >::PersonCluster | ( | const PointCloudPtr & | input_cloud, |
const pcl::PointIndices & | indices, | ||
const Eigen::VectorXf & | ground_coeffs, | ||
float | sqrt_ground_coeffs, | ||
bool | head_centroid, | ||
bool | vertical = false |
||
) |
Constructor.
Definition at line 47 of file person_cluster.hpp.
pcl::people::PersonCluster< PointT >::~PersonCluster | ( | ) | [virtual] |
Destructor.
Definition at line 429 of file person_cluster.hpp.
void pcl::people::PersonCluster< PointT >::drawTBoundingBox | ( | pcl::visualization::PCLVisualizer & | viewer, |
int | person_number | ||
) |
Draws the theoretical 3D bounding box of the cluster in the PCL visualizer.
[in] | viewer | PCL visualizer. |
[in] | person_numbers | progressive number representing the person. |
Definition at line 385 of file person_cluster.hpp.
float pcl::people::PersonCluster< PointT >::getAngle | ( | ) |
Returns the angle formed by the cluster's centroid with respect to the sensor (in radians).
Definition at line 343 of file person_cluster.hpp.
float pcl::people::PersonCluster< PointT >::getAngleMax | ( | ) |
Returns the maximum angle formed by the cluster with respect to the sensor (in radians).
Definition at line 349 of file person_cluster.hpp.
float pcl::people::PersonCluster< PointT >::getAngleMin | ( | ) |
Returns the minimum angle formed by the cluster with respect to the sensor (in radians).
Definition at line 355 of file person_cluster.hpp.
Eigen::Vector3f & pcl::people::PersonCluster< PointT >::getBottom | ( | ) |
Returns the bottom point.
Definition at line 319 of file person_cluster.hpp.
Eigen::Vector3f & pcl::people::PersonCluster< PointT >::getCenter | ( | ) |
float pcl::people::PersonCluster< PointT >::getDistance | ( | ) |
Returns the distance of the cluster from the sensor.
Definition at line 289 of file person_cluster.hpp.
float pcl::people::PersonCluster< PointT >::getHeight | ( | ) |
Returns the height of the cluster.
Definition at line 261 of file person_cluster.hpp.
pcl::PointIndices & pcl::people::PersonCluster< PointT >::getIndices | ( | ) |
Returns the indices of the point cloud points corresponding to the cluster.
Definition at line 255 of file person_cluster.hpp.
Eigen::Vector3f & pcl::people::PersonCluster< PointT >::getMax | ( | ) |
Returns the point formed by max x, max y and max z.
Definition at line 337 of file person_cluster.hpp.
Eigen::Vector3f & pcl::people::PersonCluster< PointT >::getMin | ( | ) |
Returns the point formed by min x, min y and min z.
Definition at line 331 of file person_cluster.hpp.
int pcl::people::PersonCluster< PointT >::getNumberPoints | ( | ) |
Returns the number of points of the cluster.
Definition at line 361 of file person_cluster.hpp.
float pcl::people::PersonCluster< PointT >::getPersonConfidence | ( | ) |
Returns the HOG confidence.
Definition at line 367 of file person_cluster.hpp.
Eigen::Vector3f & pcl::people::PersonCluster< PointT >::getTBottom | ( | ) |
Returns the theoretical bottom point.
Definition at line 301 of file person_cluster.hpp.
Eigen::Vector3f & pcl::people::PersonCluster< PointT >::getTCenter | ( | ) |
Returns the theoretical centroid (at half height).
Definition at line 307 of file person_cluster.hpp.
Eigen::Vector3f & pcl::people::PersonCluster< PointT >::getTop | ( | ) |
Eigen::Vector3f & pcl::people::PersonCluster< PointT >::getTTop | ( | ) |
Returns the theoretical top point.
Definition at line 295 of file person_cluster.hpp.
void pcl::people::PersonCluster< PointT >::init | ( | const PointCloudPtr & | input_cloud, |
const pcl::PointIndices & | indices, | ||
const Eigen::VectorXf & | ground_coeffs, | ||
float | sqrt_ground_coeffs, | ||
bool | head_centroid, | ||
bool | vertical | ||
) | [protected] |
PersonCluster initialization.
Definition at line 59 of file person_cluster.hpp.
void pcl::people::PersonCluster< PointT >::setHeight | ( | float | height | ) |
void pcl::people::PersonCluster< PointT >::setPersonConfidence | ( | float | confidence | ) |
Sets the HOG confidence.
[in] | confidence |
Definition at line 373 of file person_cluster.hpp.
float pcl::people::PersonCluster< PointT >::updateHeight | ( | const Eigen::VectorXf & | ground_coeffs | ) |
Update the height of the cluster.
[in] | ground_coeffs | The coefficients of the ground plane. |
Definition at line 267 of file person_cluster.hpp.
float pcl::people::PersonCluster< PointT >::updateHeight | ( | const Eigen::VectorXf & | ground_coeffs, |
float | sqrt_ground_coeffs | ||
) |
Update the height of the cluster.
[in] | ground_coeffs | The coefficients of the ground plane. |
[in] | sqrt_ground_coeffs | The norm of the vector [a, b, c] where a, b and c are the first three coefficients of the ground plane (ax + by + cz + d = 0). |
Definition at line 274 of file person_cluster.hpp.
bool operator< | ( | const PersonCluster< PointT > & | c1, |
const PersonCluster< PointT > & | c2 | ||
) | [friend] |
For sorting purpose: sort by distance.
float pcl::people::PersonCluster< PointT >::angle_ [protected] |
Cluster centroid horizontal angle with respect to z axis.
Definition at line 102 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::angle_max_ [protected] |
Maximum angle of the cluster points.
Definition at line 105 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::angle_min_ [protected] |
Minimum angle of the cluster points.
Definition at line 107 of file person_cluster.h.
Eigen::Vector3f pcl::people::PersonCluster< PointT >::bottom_ [protected] |
Cluster bottom point.
Definition at line 112 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::c_x_ [protected] |
x coordinate of the cluster centroid.
Definition at line 90 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::c_y_ [protected] |
y coordinate of the cluster centroid.
Definition at line 92 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::c_z_ [protected] |
z coordinate of the cluster centroid.
Definition at line 94 of file person_cluster.h.
Eigen::Vector3f pcl::people::PersonCluster< PointT >::center_ [protected] |
Cluster centroid.
Definition at line 114 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::distance_ [protected] |
Cluster distance from the sensor.
Definition at line 100 of file person_cluster.h.
bool pcl::people::PersonCluster< PointT >::head_centroid_ [protected] |
Definition at line 63 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::height_ [protected] |
Cluster height from the ground plane.
Definition at line 97 of file person_cluster.h.
Eigen::Vector3f pcl::people::PersonCluster< PointT >::max_ [protected] |
Vector containing the maximum coordinates of the cluster.
Definition at line 126 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::max_x_ [protected] |
Maximum x coordinate of the cluster points.
Definition at line 73 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::max_y_ [protected] |
Maximum y coordinate of the cluster points.
Definition at line 75 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::max_z_ [protected] |
Maximum z coordinate of the cluster points.
Definition at line 77 of file person_cluster.h.
Eigen::Vector3f pcl::people::PersonCluster< PointT >::min_ [protected] |
Vector containing the minimum coordinates of the cluster.
Definition at line 124 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::min_x_ [protected] |
Minimum x coordinate of the cluster points.
Definition at line 66 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::min_y_ [protected] |
Minimum y coordinate of the cluster points.
Definition at line 68 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::min_z_ [protected] |
Minimum z coordinate of the cluster points.
Definition at line 70 of file person_cluster.h.
int pcl::people::PersonCluster< PointT >::n_ [protected] |
Number of cluster points.
Definition at line 87 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::person_confidence_ [protected] |
PersonCluster HOG confidence.
Definition at line 134 of file person_cluster.h.
pcl::PointIndices pcl::people::PersonCluster< PointT >::points_indices_ [protected] |
Point cloud indices of the cluster points.
Definition at line 129 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::sum_x_ [protected] |
Sum of x coordinates of the cluster points.
Definition at line 80 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::sum_y_ [protected] |
Sum of y coordinates of the cluster points.
Definition at line 82 of file person_cluster.h.
float pcl::people::PersonCluster< PointT >::sum_z_ [protected] |
Sum of z coordinates of the cluster points.
Definition at line 84 of file person_cluster.h.
Eigen::Vector3f pcl::people::PersonCluster< PointT >::tbottom_ [protected] |
Theoretical cluster bottom (lying on the ground plane).
Definition at line 119 of file person_cluster.h.
Eigen::Vector3f pcl::people::PersonCluster< PointT >::tcenter_ [protected] |
Theoretical cluster center (between ttop_ and tbottom_).
Definition at line 121 of file person_cluster.h.
Eigen::Vector3f pcl::people::PersonCluster< PointT >::top_ [protected] |
Cluster top point.
Definition at line 110 of file person_cluster.h.
Eigen::Vector3f pcl::people::PersonCluster< PointT >::ttop_ [protected] |
Theoretical cluster top.
Definition at line 117 of file person_cluster.h.
bool pcl::people::PersonCluster< PointT >::vertical_ [protected] |
If true, the sensor is considered to be vertically placed (portrait mode).
Definition at line 132 of file person_cluster.h.