nearest.h File Reference

#include <sensor_msgs/PointCloud.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/Point32.h>
#include <geometry_msgs/Polygon.h>
#include <Eigen/Core>
#include <Eigen/QR>
Include dependency graph for nearest.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  cloud_geometry
namespace  cloud_geometry::nearest

Functions

void cloud_geometry::nearest::computeCentroid (const sensor_msgs::PointCloud &points, std::vector< int > &indices, sensor_msgs::PointCloud &centroid)
void cloud_geometry::nearest::computeCentroid (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &centroid)
 Compute the centroid of a set of points and return it as a PointCloud message with 1 value.
void cloud_geometry::nearest::computeCentroid (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, std::vector< double > &centroid)
 Compute the centroid of a set of points using their indices and return it as a Point32 message.
void cloud_geometry::nearest::computeCentroid (const sensor_msgs::PointCloudConstPtr &points, const std::vector< int > &indices, geometry_msgs::Point32 &centroid)
 Compute the centroid of a set of points using their indices and return it as a Point32 message.
void cloud_geometry::nearest::computeCentroid (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, geometry_msgs::Point32 &centroid)
 Compute the centroid of a set of points using their indices and return it as a Point32 message.
void cloud_geometry::nearest::computeCentroid (const geometry_msgs::Polygon &poly, geometry_msgs::Point32 &centroid)
 Compute the centroid of a 3D polygon and return it as a Point32 message.
void cloud_geometry::nearest::computeCentroid (const sensor_msgs::PointCloud &points, geometry_msgs::Point32 &centroid)
 Compute the centroid of a set of points and return it as a Point32 message.
void cloud_geometry::nearest::computeCovarianceMatrix (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix)
 Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d.
void cloud_geometry::nearest::computeCovarianceMatrix (const sensor_msgs::PointCloudConstPtr &points, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix, geometry_msgs::Point32 &centroid)
 Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d.
void cloud_geometry::nearest::computeCovarianceMatrix (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix, geometry_msgs::Point32 &centroid)
 Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d.
void cloud_geometry::nearest::computeCovarianceMatrix (const sensor_msgs::PointCloud &points, Eigen::Matrix3d &covariance_matrix)
 Compute the 3x3 covariance matrix of a given set of points. The result is returned as a Eigen::Matrix3d.
void cloud_geometry::nearest::computeCovarianceMatrix (const sensor_msgs::PointCloud &points, Eigen::Matrix3d &covariance_matrix, geometry_msgs::Point32 &centroid)
 Compute the 3x3 covariance matrix of a given set of points. The result is returned as a Eigen::Matrix3d.
void cloud_geometry::nearest::computeMomentInvariants (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, double &j1, double &j2, double &j3)
 Compute the 3 moment invariants (j1, j2, j3) for a given set of points, using their indices.
void cloud_geometry::nearest::computeMomentInvariants (const sensor_msgs::PointCloud &points, double &j1, double &j2, double &j3)
 Compute the 3 moment invariants (j1, j2, j3) for a given set of points.
void cloud_geometry::nearest::computeOrganizedPointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloudConstPtr &surface, int k, int downsample_factor, int width, int height, double max_z, const geometry_msgs::Point32 &viewpoint)
 Estimate the point normals and surface curvatures for a given organized point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation.
void cloud_geometry::nearest::computeOrganizedPointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface, int k, int downsample_factor, int width, int height, double max_z, const geometry_msgs::Point32 &viewpoint)
 Estimate the point normals and surface curvatures for a given organized point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation.
void cloud_geometry::nearest::computeOrganizedPointCloudNormalsWithFiltering (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface, int k, int downsample_factor, int width, int height, double max_z, double min_angle, double max_angle, const geometry_msgs::Point32 &viewpoint)
 Estimate the point normals and surface curvatures for a given organized point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation.
void cloud_geometry::nearest::computePatchEigen (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values)
 Compute the eigenvalues and eigenvectors of a given surface patch.
void cloud_geometry::nearest::computePatchEigen (const sensor_msgs::PointCloud &points, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values)
 Compute the eigenvalues and eigenvectors of a given surface patch.
void cloud_geometry::nearest::computePatchEigenNormalized (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values, geometry_msgs::Point32 &centroid)
 Compute the eigenvalues and eigenvectors of a given surface patch from its normalized covariance matrix.
void cloud_geometry::nearest::computePatchEigenNormalized (const sensor_msgs::PointCloud &points, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values, geometry_msgs::Point32 &centroid)
 Compute the eigenvalues and eigenvectors of a given surface patch from its normalized covariance matrix.
void cloud_geometry::nearest::computePointCloudNormals (sensor_msgs::PointCloud &points, double radius, const geometry_msgs::PointStamped &viewpoint)
 Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points).
void cloud_geometry::nearest::computePointCloudNormals (sensor_msgs::PointCloud &points, int k, const geometry_msgs::PointStamped &viewpoint)
 Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points).
void cloud_geometry::nearest::computePointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface, double radius, const geometry_msgs::PointStamped &viewpoint)
 Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation.
void cloud_geometry::nearest::computePointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface, int k, const geometry_msgs::PointStamped &viewpoint)
 Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation.
void cloud_geometry::nearest::computePointNormal (const sensor_msgs::PointCloudConstPtr &points, const std::vector< int > &indices, Eigen::Vector4d &plane_parameters, double &curvature)
 Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature.
void cloud_geometry::nearest::computePointNormal (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, Eigen::Vector4d &plane_parameters, double &curvature)
 Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature.
void cloud_geometry::nearest::computePointNormal (const sensor_msgs::PointCloud &points, Eigen::Vector4d &plane_parameters, double &curvature)
 Compute the Least-Squares plane fit for a given set of points, and return the estimated plane parameters together with the surface curvature.
void cloud_geometry::nearest::extractEuclideanClusters (const sensor_msgs::PointCloud &points, double tolerance, std::vector< std::vector< int > > &clusters, int nx_idx, int ny_idx, int nz_idx, double eps_angle, unsigned int min_pts_per_cluster)
 Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation : assumes normalized point normals !
void cloud_geometry::nearest::extractEuclideanClusters (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, double tolerance, std::vector< std::vector< int > > &clusters, int nx_idx, int ny_idx, int nz_idx, double eps_angle, unsigned int min_pts_per_cluster)
 Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation : assumes normalized point normals !
void cloud_geometry::nearest::filterJumpEdges (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &points_filtered, int k, int width, int height, double min_angle, double max_angle, const geometry_msgs::Point32 &viewpoint)
 Filter jump edges in an organized point cloud dataset (e.g., acquired using TOF or dense stereo, etc).
double cloud_geometry::nearest::getAngleWithViewpoint (float px, float py, float pz, float qx, float qy, float qz, float vp_x=0, float vp_y=0, float vp_z=0)
 Computes the angle between the lines created from 2 points and the viewpoint: [vp->p1], [p1->p2] Returns the angle (in degrees).
bool cloud_geometry::nearest::isBoundaryPoint (const sensor_msgs::PointCloud &points, int q_idx, const std::vector< int > &neighbors, const Eigen::Vector3d &u, const Eigen::Vector3d &v, double angle_threshold)
 Check whether a point is a boundary point in a planar patch of projected points given by indices.
 All Classes Namespaces Files Functions Variables Typedefs Defines


door_handle_detector
Author(s): Radu Bogdan Rusu, Marius
autogenerated on Fri Jan 11 09:42:02 2013