#include <algorithm>#include <cfloat>#include <door_handle_detector/geometry/point.h>#include <door_handle_detector/geometry/statistics.h>
Go to the source code of this file.
Namespaces | |
| namespace | cloud_geometry |
Functions | |
| void | cloud_geometry::downsamplePointCloud (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size) |
| Downsample a Point Cloud using a voxelized grid approach. | |
| void | cloud_geometry::downsamplePointCloud (sensor_msgs::PointCloudConstPtr points, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size, std::vector< Leaf > &leaves, int d_idx, double cut_distance) |
| Downsample a Point Cloud using a voxelized grid approach. | |
| void | cloud_geometry::downsamplePointCloud (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size, std::vector< Leaf > &leaves, int d_idx, double cut_distance) |
| Downsample a Point Cloud using a voxelized grid approach. | |
| void | cloud_geometry::downsamplePointCloud (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size, std::vector< Leaf > &leaves, int d_idx, double cut_distance) |
| Downsample a Point Cloud using a voxelized grid approach. | |
| std::string | cloud_geometry::getAvailableChannels (const sensor_msgs::PointCloudConstPtr &cloud) |
| Get the available dimensions as a space separated string. | |
| std::string | cloud_geometry::getAvailableChannels (const sensor_msgs::PointCloud &cloud) |
| Get the available dimensions as a space separated string. | |
| int | cloud_geometry::getChannelIndex (sensor_msgs::PointCloudConstPtr points, std::string channel_name) |
| Get the index of a specified dimension/channel in a point cloud. | |
| int | cloud_geometry::getChannelIndex (const sensor_msgs::PointCloud &points, std::string channel_name) |
| Get the index of a specified dimension/channel in a point cloud. | |
| void | cloud_geometry::getPointCloud (const sensor_msgs::PointCloud &input, const std::vector< int > &indices, sensor_msgs::PointCloud &output) |
| Create a new point cloud object by copying the data from a given input point cloud using a set of indices. | |
| void | cloud_geometry::getPointCloudOutside (const sensor_msgs::PointCloud &input, std::vector< int > indices, sensor_msgs::PointCloud &output) |
| Create a new point cloud object by copying the data from a given input point cloud using a set of indices. | |
| void | cloud_geometry::getPointIndicesAxisParallelNormals (const sensor_msgs::PointCloud &points, int nx, int ny, int nz, double eps_angle, const geometry_msgs::Point32 &axis, std::vector< int > &indices) |
| Get the point indices from a cloud, whose normals are close to parallel with a given axis direction. | |
| void | cloud_geometry::getPointIndicesAxisPerpendicularNormals (const sensor_msgs::PointCloud &points, int nx, int ny, int nz, double eps_angle, const geometry_msgs::Point32 &axis, std::vector< int > &indices) |
| Get the point indices from a cloud, whose normals are close to perpendicular to a given axis direction. | |