Functions
cloud_geometry::statistics Namespace Reference

Functions

double computeCentralizedMoment (const sensor_msgs::PointCloud &points, double p, double q, double r)
 Compute the centralized moment at a 3D points patch.
double 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.
geometry_msgs::Point32 computeMedian (const sensor_msgs::PointCloud &points)
 Compute the median value of a 3D point cloud and return it as a Point32.
geometry_msgs::Point32 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.
double computeMedianAbsoluteDeviation (const sensor_msgs::PointCloud &points, double sigma)
 Compute the median absolute deviation:

\[ MAD = \sigma * median_i (| Xi - median_j(Xj) |) \]

.

double computeMedianAbsoluteDeviation (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, double sigma)
 Compute the median absolute deviation:

\[ MAD = \sigma * median_i (| Xi - median_j(Xj) |) \]

.

void 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 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 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 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 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 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 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 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 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 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 getMeanStd (const std::vector< int > &values, double &mean, double &stddev)
 Compute both the mean and the standard deviation of an array of values.
void 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 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 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 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 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 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 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 getTrimean (std::vector< int > values, double &trimean)
 Compute both the trimean (a statistical resistent L-Estimate) of an array of values.
void 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 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.

Function Documentation

double cloud_geometry::statistics::computeCentralizedMoment ( const sensor_msgs::PointCloud points,
double  p,
double  q,
double  r 
) [inline]

Compute the centralized moment at a 3D points patch.

Parameters:
pointsthe point cloud data message
pthe p-dimension
qthe q-dimension
rthe r-dimension

Definition at line 297 of file statistics.h.

double cloud_geometry::statistics::computeCentralizedMoment ( const sensor_msgs::PointCloud points,
const std::vector< int > &  indices,
double  p,
double  q,
double  r 
) [inline]

Compute the centralized moment at a 3D points patch, using their indices.

Parameters:
pointsthe point cloud data message
indicesthe point cloud indices that need to be used
pthe p-dimension
qthe q-dimension
rthe r-dimension

Definition at line 315 of file statistics.h.

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.

Parameters:
pointsthe point cloud data message

Definition at line 47 of file statistics.cpp.

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.

Parameters:
pointsthe point cloud data message
indicesthe point indices

Definition at line 88 of file statistics.cpp.

Compute the median absolute deviation:

\[ MAD = \sigma * median_i (| Xi - median_j(Xj) |) \]

.

Note:
Sigma needs to be chosen carefully (a good starting sigma value is 1.4826)
Parameters:
pointsthe point cloud data message
sigmathe sigma value

Definition at line 132 of file statistics.cpp.

double cloud_geometry::statistics::computeMedianAbsoluteDeviation ( const sensor_msgs::PointCloud points,
const std::vector< int > &  indices,
double  sigma 
)

Compute the median absolute deviation:

\[ MAD = \sigma * median_i (| Xi - median_j(Xj) |) \]

.

Note:
Sigma needs to be chosen carefully (a good starting sigma value is 1.4826)
Parameters:
pointsthe point cloud data message
sigmathe sigma value

Definition at line 166 of file statistics.cpp.

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.

Parameters:
pointsa pointer to the point cloud message
d_idxthe channel index
meanthe resultant mean of the distribution
stddevthe resultant standard deviation of the distribution

Definition at line 199 of file statistics.cpp.

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.

Parameters:
pointsa pointer to the point cloud message
indicesa pointer to the point cloud indices to use
d_idxthe channel index
meanthe resultant mean of the distribution
stddevthe resultant standard deviation of the distribution

Definition at line 222 of file statistics.cpp.

void cloud_geometry::statistics::getLargestDiagonalIndices ( const geometry_msgs::Polygon &  poly,
int &  min_idx,
int &  max_idx 
) [inline]

Determine the point indices that form the largest diagonal in a given set of points.

Parameters:
polythe polygon message
min_idxthe resultant index of the 'minimum' point
max_idxthe resultant index of the 'maximum' point

Definition at line 55 of file statistics.h.

void cloud_geometry::statistics::getLargestDiagonalIndices ( const sensor_msgs::PointCloud points,
int &  min_idx,
int &  max_idx 
) [inline]

Determine the point indices that form the largest diagonal in a given set of points.

Parameters:
pointsthe point cloud data message
min_idxthe resultant index of the 'minimum' point
max_idxthe resultant index of the 'maximum' point

Definition at line 83 of file statistics.h.

void cloud_geometry::statistics::getLargestDiagonalIndices ( const sensor_msgs::PointCloud points,
const std::vector< int > &  indices,
int &  min_idx,
int &  max_idx 
) [inline]

Determine the point indices that form the largest diagonal in a given set of points.

Parameters:
pointsthe point cloud data message
indicesthe point cloud indices that need to be used
min_idxthe resultant index of the 'minimum' point
max_idxthe resultant index of the 'maximum' point

Definition at line 112 of file statistics.h.

void cloud_geometry::statistics::getLargestDiagonalPoints ( const geometry_msgs::Polygon &  poly,
geometry_msgs::Point32 &  min_p,
geometry_msgs::Point32 &  max_p 
) [inline]

Determine the points that form the largest diagonal in a given set of points.

Parameters:
polythe polygon message
minPthe resultant minimum point in the set
maxPthe resultant maximum point in the set

Definition at line 140 of file statistics.h.

void cloud_geometry::statistics::getLargestDiagonalPoints ( const sensor_msgs::PointCloud points,
geometry_msgs::Point32 &  min_p,
geometry_msgs::Point32 &  max_p 
) [inline]

Determine the points that form the largest diagonal in a given set of points.

Parameters:
pointsthe point cloud data message
minPthe resultant minimum point in the set
maxPthe resultant maximum point in the set

Definition at line 168 of file statistics.h.

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 
) [inline]

Determine the points that form the largest diagonal in a given set of points.

Parameters:
pointsthe point cloud data message
indicesthe point cloud indices that need to be used
minPthe resultant minimum point in the set
maxPthe resultant maximum point in the set

Definition at line 197 of file statistics.h.

void cloud_geometry::statistics::getLargestXYPoints ( const geometry_msgs::Polygon &  poly,
geometry_msgs::Point32 &  min_p,
geometry_msgs::Point32 &  max_p 
) [inline]

Determine the points that form the largest diagonal in a given set of points.

Parameters:
polythe polygon message
minPthe resultant minimum point in the set
maxPthe resultant maximum point in the set

Definition at line 233 of file statistics.h.

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 
) [inline]

Determine the points that form the largest diagonal in a given set of points.

Parameters:
pointsthe point cloud data message
indicesthe point cloud indices that need to be used
minPthe resultant minimum point in the set
maxPthe resultant maximum point in the set

Definition at line 262 of file statistics.h.

void cloud_geometry::statistics::getMeanStd ( const std::vector< int > &  values,
double &  mean,
double &  stddev 
) [inline]

Compute both the mean and the standard deviation of an array of values.

Parameters:
valuesthe array of values
meanthe resultant mean of the distribution
stddevthe resultant standard deviation of the distribution

Definition at line 535 of file statistics.h.

void cloud_geometry::statistics::getMinMax ( const sensor_msgs::PointCloud points,
geometry_msgs::Point32 &  minP,
geometry_msgs::Point32 &  maxP 
) [inline]

Determine the minimum and maximum 3D bounding box coordinates for a given point cloud.

Parameters:
pointsthe point cloud message
minPthe resultant minimum bounding box coordinates
maxPthe resultant maximum bounding box coordinates

Definition at line 331 of file statistics.h.

void cloud_geometry::statistics::getMinMax ( const geometry_msgs::Polygon &  poly,
geometry_msgs::Point32 &  min_p,
geometry_msgs::Point32 &  max_p 
) [inline]

Determine the minimum and maximum 3D bounding box coordinates for a given 3D polygon.

Parameters:
polythe polygon message
min_pthe resultant minimum bounding box coordinates
max_pthe resultant maximum bounding box coordinates

Definition at line 356 of file statistics.h.

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 
) [inline]

Determine the minimum and maximum 3D bounding box coordinates for a given point cloud, using point indices.

Parameters:
pointsthe point cloud message
indicesthe point cloud indices to use
min_pthe resultant minimum bounding box coordinates
max_pthe resultant maximum bounding box coordinates

Definition at line 381 of file statistics.h.

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 
) [inline]

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.

Parameters:
pointsthe point cloud data message
min_ptthe resultant minimum bounds
max_ptthe resultant maximum bounds
c_idxthe index of the channel holding distance information
cut_distancea maximum admissible distance threshold for points from the laser origin

Definition at line 408 of file statistics.h.

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 
) [inline]

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.

Parameters:
pointsthe point cloud data message
min_ptthe resultant minimum bounds
max_ptthe resultant maximum bounds
c_idxthe index of the channel holding distance information
cut_distancea maximum admissible distance threshold for points from the laser origin

Definition at line 438 of file statistics.h.

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 
) [inline]

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.

Parameters:
pointsthe point cloud data message
indicesthe point cloud indices to use
min_ptthe resultant minimum bounds
max_ptthe resultant maximum bounds
c_idxthe index of the channel holding distance information
cut_distancea maximum admissible distance threshold for points from the laser origin

Definition at line 469 of file statistics.h.

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 
) [inline]

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.

Parameters:
pointsthe point cloud data message
indicesthe point cloud indices to use
min_ptthe resultant minimum bounds
max_ptthe resultant maximum bounds
c_idxthe index of the channel holding distance information
cut_distancea maximum admissible distance threshold for points from the laser origin

Definition at line 500 of file statistics.h.

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.

Note:
The trimean is computed by adding the 25th percentile plus twice the 50th percentile plus the 75th percentile and dividing by four.
Parameters:
valuesthe array of values
trimeanthe resultant trimean of the distribution

Definition at line 304 of file statistics.cpp.

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.

Parameters:
pointsa pointer to the point cloud message
indicesa pointer to the point cloud indices to use
d_idxthe channel index
meanthe mean of the distribution
stddevthe standard deviation of the distribution
alphaa multiplication factor for stddev
inliersthe resultant point indices

Definition at line 278 of file statistics.cpp.

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.

Parameters:
pointsa pointer to the point cloud message
indicesa pointer to the point cloud indices to use
d_idxthe channel index
meanthe mean of the distribution
stddevthe standard deviation of the distribution
alphaa multiplication factor for stddev
inliersthe resultant point indices

Definition at line 248 of file statistics.cpp.



door_handle_detector
Author(s): Radu Bogdan Rusu, Marius
autogenerated on Wed Dec 11 2013 14:17:01