Various point cloud metric calculations and utilities. More...
#include <geometry_msgs/Point.h>#include <graspdb/Grasp.h>#include <sensor_msgs/PointCloud2.h>#include <tf2/LinearMath/Transform.h>#include <pcl/point_cloud.h>#include <pcl/point_types.h>#include <vector>

Go to the source code of this file.
Namespaces | |
| namespace | rail |
| namespace | rail::pick_and_place |
| namespace | rail::pick_and_place::point_cloud_metrics |
Functions | |
| void | rail::pick_and_place::point_cloud_metrics::calculateAvgColors (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &pc, double &avg_r, double &avg_g, double &avg_b) |
| Average color value calculator. | |
| double | rail::pick_and_place::point_cloud_metrics::calculateRegistrationMetricDistanceError (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &base, const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &target) |
| Point cloud distance error metric calculator. | |
| void | rail::pick_and_place::point_cloud_metrics::calculateRegistrationMetricOverlap (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &base, const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &target, double &overlap, double &color_error, const double metric_overlap_search_radius=DEFAULT_METRIC_OVERLAP_SEARCH_RADIUS) |
| Point cloud overlap metric calculator. | |
| double | rail::pick_and_place::point_cloud_metrics::calculateStdDevColors (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &pc, double &std_dev_r, double &std_dev_g, double &std_dev_b) |
| Color value standard deviation calculator. | |
| double | rail::pick_and_place::point_cloud_metrics::calculateStdDevColors (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &pc, double &std_dev_r, double &std_dev_g, double &std_dev_b, const double avg_r, const double avg_g, const double avg_b) |
| Color value standard deviation calculator. | |
| bool | rail::pick_and_place::point_cloud_metrics::classifyMerge (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &base, const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &target) |
| Classify the point cloud merge. | |
| geometry_msgs::Point | rail::pick_and_place::point_cloud_metrics::computeCentroid (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &pc) |
| Compute the centroid of the given point cloud. | |
| void | rail::pick_and_place::point_cloud_metrics::filterPointCloudOutliers (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pc, const double filter_outlier_search_radius=DEFAULT_FILTER_OUTLIER_SEARCH_RADIUS, const double filter_outlier_min_num_neighbors=DEFAULT_FILTER_OUTLIER_MIN_NUM_NEIGHBORS) |
| Filter point cloud outliers. | |
| void | rail::pick_and_place::point_cloud_metrics::filterRedundantPoints (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pc, const double filter_redundant_search_radius=DEFAULT_FILTER_REDUNDANT_SEARCH_RADIUS) |
| Filter redundant points from the point cloud. | |
| void | rail::pick_and_place::point_cloud_metrics::pclPointCloudToROSPointCloud2 (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &in, sensor_msgs::PointCloud2 &out) |
| Convert a PCL point cloud to a ROS point cloud message. | |
| tf2::Transform | rail::pick_and_place::point_cloud_metrics::performICP (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &target, const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &source, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &result) |
| Perform ICP on the given point clouds. | |
| void | rail::pick_and_place::point_cloud_metrics::rosPointCloud2ToPCLPointCloud (const sensor_msgs::PointCloud2 in, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &out) |
| Convert a ROS point cloud message to a PCL point cloud. | |
| void | rail::pick_and_place::point_cloud_metrics::transformToOrigin (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pc, const geometry_msgs::Point ¢roid) |
| Transform the point cloud to be centered about the origin. | |
| void | rail::pick_and_place::point_cloud_metrics::transformToOrigin (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pc) |
| Transform the point cloud to be centered about the origin. | |
| void | rail::pick_and_place::point_cloud_metrics::transformToOrigin (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pc, std::vector< graspdb::Grasp > &grasps, const geometry_msgs::Point ¢roid) |
| Transform the point cloud and grasps to be centered about the origin. | |
| void | rail::pick_and_place::point_cloud_metrics::transformToOrigin (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pc, std::vector< graspdb::Grasp > &grasps) |
| Transform the point cloud and grasps to be centered about the origin. | |
Variables | |
| static const int | rail::pick_and_place::point_cloud_metrics::DEFAULT_FILTER_OUTLIER_MIN_NUM_NEIGHBORS = 6 |
| static const double | rail::pick_and_place::point_cloud_metrics::DEFAULT_FILTER_OUTLIER_SEARCH_RADIUS = 0.01 |
| static const double | rail::pick_and_place::point_cloud_metrics::DEFAULT_FILTER_REDUNDANT_SEARCH_RADIUS = 0.0004 |
| static const double | rail::pick_and_place::point_cloud_metrics::DEFAULT_METRIC_OVERLAP_SEARCH_RADIUS = 0.005 |
Various point cloud metric calculations and utilities.
A collection of static functions for calculating various point cloud metrics and utility functions.
Definition in file PointCloudMetrics.h.