#include <sensor_msgs/PointCloud.h>
#include <geometry_msgs/Point32.h>
#include <geometry_msgs/Polygon.h>
#include <cfloat>
Go to the source code of this file.
Namespaces | |
namespace | cloud_geometry |
namespace | cloud_geometry::statistics |
Functions | |
double | cloud_geometry::statistics::computeCentralizedMoment (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, double p, double q, double r) |
Compute the centralized moment at a 3D points patch, using their indices. | |
double | cloud_geometry::statistics::computeCentralizedMoment (const sensor_msgs::PointCloud &points, double p, double q, double r) |
Compute the centralized moment at a 3D points patch. | |
geometry_msgs::Point32 | cloud_geometry::statistics::computeMedian (const sensor_msgs::PointCloud &points, const std::vector< int > &indices) |
Compute the median value of a 3D point cloud using a given set point indices and return it as a Point32. | |
geometry_msgs::Point32 | cloud_geometry::statistics::computeMedian (const sensor_msgs::PointCloud &points) |
Compute the median value of a 3D point cloud and return it as a Point32. | |
double | cloud_geometry::statistics::computeMedianAbsoluteDeviation (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, double sigma) |
Compute the median absolute deviation:
| |
double | cloud_geometry::statistics::computeMedianAbsoluteDeviation (const sensor_msgs::PointCloud &points, double sigma) |
Compute the median absolute deviation:
| |
void | cloud_geometry::statistics::getChannelMeanStd (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, int d_idx, double &mean, double &stddev) |
Compute both the mean and the standard deviation of a channel/dimension of the cloud using indices. | |
void | cloud_geometry::statistics::getChannelMeanStd (const sensor_msgs::PointCloud &points, int d_idx, double &mean, double &stddev) |
Compute both the mean and the standard deviation of a channel/dimension of the cloud. | |
void | cloud_geometry::statistics::getLargestDiagonalIndices (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, int &min_idx, int &max_idx) |
Determine the point indices that form the largest diagonal in a given set of points. | |
void | cloud_geometry::statistics::getLargestDiagonalIndices (const sensor_msgs::PointCloud &points, int &min_idx, int &max_idx) |
Determine the point indices that form the largest diagonal in a given set of points. | |
void | cloud_geometry::statistics::getLargestDiagonalIndices (const geometry_msgs::Polygon &poly, int &min_idx, int &max_idx) |
Determine the point indices that form the largest diagonal in a given set of points. | |
void | cloud_geometry::statistics::getLargestDiagonalPoints (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p) |
Determine the points that form the largest diagonal in a given set of points. | |
void | cloud_geometry::statistics::getLargestDiagonalPoints (const sensor_msgs::PointCloud &points, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p) |
Determine the points that form the largest diagonal in a given set of points. | |
void | cloud_geometry::statistics::getLargestDiagonalPoints (const geometry_msgs::Polygon &poly, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p) |
Determine the points that form the largest diagonal in a given set of points. | |
void | cloud_geometry::statistics::getLargestXYPoints (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p) |
Determine the points that form the largest diagonal in a given set of points. | |
void | cloud_geometry::statistics::getLargestXYPoints (const geometry_msgs::Polygon &poly, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p) |
Determine the points that form the largest diagonal in a given set of points. | |
void | cloud_geometry::statistics::getMeanStd (const std::vector< int > &values, double &mean, double &stddev) |
Compute both the mean and the standard deviation of an array of values. | |
void | cloud_geometry::statistics::getMinMax (sensor_msgs::PointCloudConstPtr points, const std::vector< int > &indices, geometry_msgs::Point32 &min_pt, geometry_msgs::Point32 &max_pt, int c_idx, double cut_distance) |
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin. | |
void | cloud_geometry::statistics::getMinMax (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, geometry_msgs::Point32 &min_pt, geometry_msgs::Point32 &max_pt, int c_idx, double cut_distance) |
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin. | |
void | cloud_geometry::statistics::getMinMax (sensor_msgs::PointCloudConstPtr points, geometry_msgs::Point32 &min_pt, geometry_msgs::Point32 &max_pt, int c_idx, double cut_distance) |
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin. | |
void | cloud_geometry::statistics::getMinMax (const sensor_msgs::PointCloud &points, geometry_msgs::Point32 &min_pt, geometry_msgs::Point32 &max_pt, int c_idx, double cut_distance) |
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin. | |
void | cloud_geometry::statistics::getMinMax (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p) |
Determine the minimum and maximum 3D bounding box coordinates for a given point cloud, using point indices. | |
void | cloud_geometry::statistics::getMinMax (const geometry_msgs::Polygon &poly, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p) |
Determine the minimum and maximum 3D bounding box coordinates for a given 3D polygon. | |
void | cloud_geometry::statistics::getMinMax (const sensor_msgs::PointCloud &points, geometry_msgs::Point32 &minP, geometry_msgs::Point32 &maxP) |
Determine the minimum and maximum 3D bounding box coordinates for a given point cloud. | |
void | cloud_geometry::statistics::getTrimean (std::vector< int > values, double &trimean) |
Compute both the trimean (a statistical resistent L-Estimate) of an array of values. | |
void | cloud_geometry::statistics::selectPointsInsideDistribution (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, int d_idx, double mean, double stddev, double alpha, std::vector< int > &inliers) |
Determines a set of point indices inside of a +/- * distribution interval, in a given channel space, where and are the mean and the standard deviation of the channel distribution. | |
void | cloud_geometry::statistics::selectPointsOutsideDistribution (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, int d_idx, double mean, double stddev, double alpha, std::vector< int > &inliers) |
Determines a set of point indices outside of a +/- * distribution interval, in a given channel space, where and are the mean and the standard deviation of the channel distribution. |