#include <point_cloud_segmentation.h>
Public Member Functions | |
| bool | cloudsIntersect (XYZPointCloud cloud0, XYZPointCloud cloud1) |
| bool | cloudsIntersect (XYZPointCloud cloud0, XYZPointCloud cloud1, double thresh) |
| void | clusterProtoObjects (XYZPointCloud &objects_cloud, ProtoObjects &objs) |
| cv::Mat | displayObjectImage (cv::Mat &obj_img, std::string win_name="projected objects", bool use_display=true) |
| void | downsampleCloud (XYZPointCloud &cloud_in, XYZPointCloud &cloud_down) |
| void | findTabletopObjects (XYZPointCloud &input_cloud, ProtoObjects &objs, bool use_mps=false) |
| void | findTabletopObjects (XYZPointCloud &input_cloud, ProtoObjects &objs, XYZPointCloud &objs_cloud, bool use_mps=false) |
| void | findTabletopObjects (XYZPointCloud &input_cloud, ProtoObjects &objs, XYZPointCloud &objs_cloud, XYZPointCloud &plane_cloud, bool use_mps=false) |
| void | fitCylinderRANSAC (ProtoObject &obj, XYZPointCloud &cylinder_cloud, pcl16::ModelCoefficients &cylinder) |
| void | fitSphereRANSAC (ProtoObject &obj, XYZPointCloud &sphere_cloud, pcl16::ModelCoefficients &sphere) |
| void | getMovedRegions (XYZPointCloud &prev_cloud, XYZPointCloud &cur_cloud, ProtoObjects &moved_regions, std::string suf="") |
| Eigen::Vector4f | getTableCentroid () const |
| void | getTablePlane (XYZPointCloud &cloud, XYZPointCloud &objs_cloud, XYZPointCloud &plane_cloud, Eigen::Vector4f ¢er, bool find_hull=false, bool find_centroid=false) |
| void | getTablePlaneMPS (XYZPointCloud &cloud, XYZPointCloud &objs_cloud, XYZPointCloud &plane_cloud, Eigen::Vector4f ¢er, bool find_hull=false, bool find_centroid=false) |
| double | ICPBoundarySamples (XYZPointCloud &hull_t_0, XYZPointCloud &hull_t_1, Eigen::Matrix4f &transform, XYZPointCloud &aligned) |
| double | ICPProtoObjects (ProtoObject &a, ProtoObject &b, Eigen::Matrix4f &transform) |
| void | lineCloudIntersection (XYZPointCloud &cloud, Eigen::Vector3f vec, Eigen::Vector4f base, XYZPointCloud &line_cloud) |
| void | lineCloudIntersectionEndPoints (XYZPointCloud &cloud, Eigen::Vector3f vec, Eigen::Vector4f base, std::vector< pcl16::PointXYZ > &end_points) |
| void | matchMovedRegions (ProtoObjects &objs, ProtoObjects &moved_regions) |
| PointCloudSegmentation (boost::shared_ptr< tf::TransformListener > tf) | |
| bool | pointIntersectsCloud (XYZPointCloud cloud, geometry_msgs::Point pt, double thresh) |
| float | pointLineXYDist (pcl16::PointXYZ p, Eigen::Vector3f vec, Eigen::Vector4f base) |
| void | projectPointCloudIntoImage (XYZPointCloud &cloud, cv::Mat &lbl_img, std::string target_frame, unsigned int id=1) |
| void | projectPointCloudIntoImage (XYZPointCloud &cloud, cv::Mat &lbl_img) |
| cv::Point | projectPointIntoImage (pcl16::PointXYZ cur_point_pcl, std::string point_frame, std::string target_frame) |
| cv::Point | projectPointIntoImage (geometry_msgs::PointStamped cur_point) |
| cv::Point | projectPointIntoImage (geometry_msgs::PointStamped cur_point, std::string target_frame) |
| cv::Point | projectPointIntoImage (Eigen::Vector3f cur_point_eig, std::string point_frame, std::string target_frame) |
| cv::Mat | projectProtoObjectIntoImage (ProtoObject &obj, cv::Size img_size, std::string target_frame) |
| cv::Mat | projectProtoObjectsIntoImage (ProtoObjects &objs, cv::Size img_size, std::string target_frame) |
Static Public Member Functions | |
| static double | dist (pcl16::PointXYZ a, pcl16::PointXYZ b) |
| static double | dist (geometry_msgs::Point b, pcl16::PointXYZ a) |
| static double | dist (pcl16::PointXYZ a, geometry_msgs::Point b) |
| static double | sqrDist (Eigen::Vector3f &a, pcl16::PointXYZ &b) |
| static double | sqrDist (Eigen::Vector4f &a, Eigen::Vector4f &b) |
| static double | sqrDist (pcl16::PointXYZ a, pcl16::PointXYZ b) |
| static double | sqrDistXY (pcl16::PointXYZ a, pcl16::PointXYZ b) |
Public Attributes | |
| sensor_msgs::CameraInfo | cam_info_ |
| double | cloud_diff_thresh_ |
| double | cloud_intersect_thresh_ |
| double | cluster_tolerance_ |
| std::vector< cv::Vec3f > | colors_ |
| std_msgs::Header | cur_camera_header_ |
| double | cylinder_ransac_angle_thresh_ |
| double | cylinder_ransac_thresh_ |
| double | hull_alpha_ |
| double | icp_max_cor_dist_ |
| int | icp_max_iters_ |
| double | icp_ransac_thresh_ |
| double | icp_transform_eps_ |
| int | max_cluster_size_ |
| double | max_table_z_ |
| double | max_workspace_x_ |
| double | max_workspace_z_ |
| int | min_cluster_size_ |
| double | min_table_z_ |
| double | min_workspace_x_ |
| double | min_workspace_z_ |
| int | moved_count_thresh_ |
| double | mps_min_angle_thresh_ |
| double | mps_min_dist_thresh_ |
| int | mps_min_inliers_ |
| int | num_downsamples_ |
| bool | optimize_cylinder_coefficients_ |
| double | sphere_ransac_thresh_ |
| double | table_ransac_angle_thresh_ |
| double | table_ransac_thresh_ |
| bool | use_voxel_down_ |
| double | voxel_down_res_ |
Protected Attributes | |
| Eigen::Vector4f | table_centroid_ |
| boost::shared_ptr < tf::TransformListener > | tf_ |
Definition at line 85 of file point_cloud_segmentation.h.
| tabletop_pushing::PointCloudSegmentation::PointCloudSegmentation | ( | boost::shared_ptr< tf::TransformListener > | tf | ) |
Definition at line 85 of file point_cloud_segmentation.cpp.
| bool tabletop_pushing::PointCloudSegmentation::cloudsIntersect | ( | XYZPointCloud | cloud0, |
| XYZPointCloud | cloud1 | ||
| ) |
Naively determine if two point clouds intersect based on distance threshold between points.
| cloud0 | First cloud for interesection test |
| cloud1 | Second cloud for interesection test |
Definition at line 625 of file point_cloud_segmentation.cpp.
| bool tabletop_pushing::PointCloudSegmentation::cloudsIntersect | ( | XYZPointCloud | cloud0, |
| XYZPointCloud | cloud1, | ||
| double | thresh | ||
| ) |
Definition at line 647 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::clusterProtoObjects | ( | XYZPointCloud & | objects_cloud, |
| ProtoObjects & | objs | ||
| ) |
Function to segment point cloud regions using euclidean clustering
| objects_cloud | The cloud of objects to cluster |
| objs | [Returned] The independent clusters |
Definition at line 393 of file point_cloud_segmentation.cpp.
| cv::Mat tabletop_pushing::PointCloudSegmentation::displayObjectImage | ( | cv::Mat & | obj_img, |
| std::string | win_name = "projected objects", |
||
| bool | use_display = true |
||
| ) |
Visualization function of proto objects projected into an image
| obj_img | The projected objects image |
| objs | The set of proto objects |
Definition at line 871 of file point_cloud_segmentation.cpp.
| static double tabletop_pushing::PointCloudSegmentation::dist | ( | pcl16::PointXYZ | a, |
| pcl16::PointXYZ | b | ||
| ) | [inline, static] |
Definition at line 193 of file point_cloud_segmentation.h.
| static double tabletop_pushing::PointCloudSegmentation::dist | ( | geometry_msgs::Point | b, |
| pcl16::PointXYZ | a | ||
| ) | [inline, static] |
Definition at line 201 of file point_cloud_segmentation.h.
| static double tabletop_pushing::PointCloudSegmentation::dist | ( | pcl16::PointXYZ | a, |
| geometry_msgs::Point | b | ||
| ) | [inline, static] |
Definition at line 206 of file point_cloud_segmentation.h.
| void tabletop_pushing::PointCloudSegmentation::downsampleCloud | ( | XYZPointCloud & | cloud_in, |
| XYZPointCloud & | cloud_down | ||
| ) |
Filter a point cloud to only be above the estimated table and within the workspace in x, then downsample the voxels.
| cloud_in | The cloud to filter and downsample |
Definition at line 798 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::findTabletopObjects | ( | XYZPointCloud & | input_cloud, |
| ProtoObjects & | objs, | ||
| bool | use_mps = false |
||
| ) |
Function to segment independent spatial regions from a supporting plane
| input_cloud | The point cloud to operate on. |
| objs | [Returned] The object clusters. |
| extract_table | True if the table plane should be extracted |
Function to segment independent spatial regions from a supporting plane
| input_cloud | The point cloud to operate on. |
| extract_table | True if the table plane should be extracted |
Definition at line 301 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::findTabletopObjects | ( | XYZPointCloud & | input_cloud, |
| ProtoObjects & | objs, | ||
| XYZPointCloud & | objs_cloud, | ||
| bool | use_mps = false |
||
| ) |
Function to segment independent spatial regions from a supporting plane
| input_cloud | The point cloud to operate on. |
| objs | [Returned] The object clusters. |
| objs_cloud | The point cloud containing the object points. |
| extract_table | True if the table plane should be extracted |
Function to segment independent spatial regions from a supporting plane
| input_cloud | The point cloud to operate on. |
| objs_cloud | The point cloud containing the object points. |
| extract_table | True if the table plane should be extracted |
Definition at line 316 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::findTabletopObjects | ( | XYZPointCloud & | input_cloud, |
| ProtoObjects & | objs, | ||
| XYZPointCloud & | objs_cloud, | ||
| XYZPointCloud & | plane_cloud, | ||
| bool | use_mps = false |
||
| ) |
Function to segment independent spatial regions from a supporting plane
| input_cloud | The point cloud to operate on. |
| objs | [Returned] The object clusters. |
| objs_cloud | The point cloud containing the object points. |
| plane_cloud | The point cloud containing the table plane points. |
| extract_table | True if the table plane should be extracted |
Function to segment independent spatial regions from a supporting plane
| input_cloud | The point cloud to operate on. |
| objs_cloud | The point cloud containing the object points. |
| plane_cloud | The point cloud containing the table plane points. |
| extract_table | True if the table plane should be extracted |
Definition at line 333 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::fitCylinderRANSAC | ( | ProtoObject & | obj, |
| XYZPointCloud & | cylinder_cloud, | ||
| pcl16::ModelCoefficients & | coefficients | ||
| ) |
Method to fit a cylinder to a segmented object
| obj | The segmented object we are modelling as a cylinder |
| cylinder_cloud | The cloud resulting from the cylinder fit |
| coefficients | [Returned] The model of the cylinder |
Definition at line 565 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::fitSphereRANSAC | ( | ProtoObject & | obj, |
| XYZPointCloud & | sphere_cloud, | ||
| pcl16::ModelCoefficients & | coefficients | ||
| ) |
Method to fit a sphere to a segmented object
| obj | The segmented object we are modelling as a sphere |
| sphere_cloud | The cloud resulting from the sphere fit |
| coefficients | [Returned] The model of the sphere |
Definition at line 599 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::getMovedRegions | ( | XYZPointCloud & | prev_cloud, |
| XYZPointCloud & | cur_cloud, | ||
| ProtoObjects & | moved, | ||
| std::string | suf = "" |
||
| ) |
Find the regions that have moved between two point clouds
| prev_cloud | The first cloud to use in differencing |
| cur_cloud | The second cloud to use |
| moved_regions | [Returned] The new set of objects that have moved in the second cloud |
| suf | [Optional] |
Definition at line 505 of file point_cloud_segmentation.cpp.
| Eigen::Vector4f tabletop_pushing::PointCloudSegmentation::getTableCentroid | ( | ) | const [inline] |
Definition at line 328 of file point_cloud_segmentation.h.
| void tabletop_pushing::PointCloudSegmentation::getTablePlane | ( | XYZPointCloud & | cloud, |
| XYZPointCloud & | objs_cloud, | ||
| XYZPointCloud & | plane_cloud, | ||
| Eigen::Vector4f & | center, | ||
| bool | find_hull = false, |
||
| bool | find_centroid = false |
||
| ) |
Function to find the table plane in the image by plane RANSAC
| cloud | The input cloud |
| objs_cloud | [Returned] the cloud not containing the table plane |
| plane_cloud | [Returned the cloud containing the plane |
| center | [Returned] the center of the table plane |
| find_hull | set true to estimate the extent of the plane |
Definition at line 97 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::getTablePlaneMPS | ( | XYZPointCloud & | cloud, |
| XYZPointCloud & | objs_cloud, | ||
| XYZPointCloud & | plane_cloud, | ||
| Eigen::Vector4f & | center, | ||
| bool | find_hull = false, |
||
| bool | find_centroid = false |
||
| ) |
Function to find the table plane in the image by using multi-plane segmentation (requires structured input cloud)
| cloud | The input cloud |
| objs_cloud | [Returned] the cloud not containing the table plane |
| plane_cloud | [Returned the cloud containing the plane |
| center | [Returned] the center of the table plane |
| find_hull | set true to estimate the extent of the plane |
Definition at line 217 of file point_cloud_segmentation.cpp.
| double tabletop_pushing::PointCloudSegmentation::ICPBoundarySamples | ( | XYZPointCloud & | hull_t_0, |
| XYZPointCloud & | hull_t_1, | ||
| Eigen::Matrix4f & | transform, | ||
| XYZPointCloud & | aligned | ||
| ) |
Perform Iterated Closest Point between two object boundaries.
| a | The first object boundary |
| b | The second object boundary |
| transform | The transform from a to b |
Definition at line 479 of file point_cloud_segmentation.cpp.
| double tabletop_pushing::PointCloudSegmentation::ICPProtoObjects | ( | ProtoObject & | a, |
| ProtoObject & | b, | ||
| Eigen::Matrix4f & | transform | ||
| ) |
Perform Iterated Closest Point between two proto objects.
| a | The first object |
| b | The second object |
Definition at line 451 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::lineCloudIntersection | ( | XYZPointCloud & | cloud, |
| Eigen::Vector3f | vec, | ||
| Eigen::Vector4f | base, | ||
| XYZPointCloud & | line_cloud | ||
| ) |
Definition at line 683 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::lineCloudIntersectionEndPoints | ( | XYZPointCloud & | cloud, |
| Eigen::Vector3f | vec, | ||
| Eigen::Vector4f | base, | ||
| std::vector< pcl16::PointXYZ > & | end_points | ||
| ) |
Definition at line 706 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::matchMovedRegions | ( | ProtoObjects & | objs, |
| ProtoObjects & | moved_regions | ||
| ) |
Match moved regions to previously extracted protoobjects
| objs | The previously extracted objects |
| moved_regions | The regions that have been detected as having moved |
Definition at line 539 of file point_cloud_segmentation.cpp.
| bool tabletop_pushing::PointCloudSegmentation::pointIntersectsCloud | ( | XYZPointCloud | cloud, |
| geometry_msgs::Point | pt, | ||
| double | thresh | ||
| ) |
Definition at line 661 of file point_cloud_segmentation.cpp.
| float tabletop_pushing::PointCloudSegmentation::pointLineXYDist | ( | pcl16::PointXYZ | p, |
| Eigen::Vector3f | vec, | ||
| Eigen::Vector4f | base | ||
| ) |
Definition at line 671 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::projectPointCloudIntoImage | ( | XYZPointCloud & | cloud, |
| cv::Mat & | lbl_img, | ||
| std::string | target_frame, | ||
| unsigned int | id = 1 |
||
| ) |
Definition at line 894 of file point_cloud_segmentation.cpp.
| void tabletop_pushing::PointCloudSegmentation::projectPointCloudIntoImage | ( | XYZPointCloud & | cloud, |
| cv::Mat & | lbl_img | ||
| ) |
Definition at line 932 of file point_cloud_segmentation.cpp.
| cv::Point tabletop_pushing::PointCloudSegmentation::projectPointIntoImage | ( | pcl16::PointXYZ | cur_point_pcl, |
| std::string | point_frame, | ||
| std::string | target_frame | ||
| ) |
| cv::Point tabletop_pushing::PointCloudSegmentation::projectPointIntoImage | ( | geometry_msgs::PointStamped | cur_point | ) |
Definition at line 944 of file point_cloud_segmentation.cpp.
| cv::Point tabletop_pushing::PointCloudSegmentation::projectPointIntoImage | ( | geometry_msgs::PointStamped | cur_point, |
| std::string | target_frame | ||
| ) |
Definition at line 950 of file point_cloud_segmentation.cpp.
| cv::Point tabletop_pushing::PointCloudSegmentation::projectPointIntoImage | ( | Eigen::Vector3f | cur_point_eig, |
| std::string | point_frame, | ||
| std::string | target_frame | ||
| ) |
Definition at line 908 of file point_cloud_segmentation.cpp.
| cv::Mat tabletop_pushing::PointCloudSegmentation::projectProtoObjectIntoImage | ( | ProtoObject & | obj, |
| cv::Size | img_size, | ||
| std::string | target_frame | ||
| ) |
Method to project the current proto object into an image
| obj | The objects |
| img_in | An image of correct size for the projection |
| target_frame | The frame of the associated image |
Definition at line 857 of file point_cloud_segmentation.cpp.
| cv::Mat tabletop_pushing::PointCloudSegmentation::projectProtoObjectsIntoImage | ( | ProtoObjects & | objs, |
| cv::Size | img_size, | ||
| std::string | target_frame | ||
| ) |
Method to project the current proto objects into an image
| objs | The set of objects |
| img_in | An image of correct size for the projection |
| target_frame | The frame of the associated image |
Definition at line 835 of file point_cloud_segmentation.cpp.
| static double tabletop_pushing::PointCloudSegmentation::sqrDist | ( | Eigen::Vector3f & | a, |
| pcl16::PointXYZ & | b | ||
| ) | [inline, static] |
Definition at line 214 of file point_cloud_segmentation.h.
| static double tabletop_pushing::PointCloudSegmentation::sqrDist | ( | Eigen::Vector4f & | a, |
| Eigen::Vector4f & | b | ||
| ) | [inline, static] |
Definition at line 222 of file point_cloud_segmentation.h.
| static double tabletop_pushing::PointCloudSegmentation::sqrDist | ( | pcl16::PointXYZ | a, |
| pcl16::PointXYZ | b | ||
| ) | [inline, static] |
Definition at line 230 of file point_cloud_segmentation.h.
| static double tabletop_pushing::PointCloudSegmentation::sqrDistXY | ( | pcl16::PointXYZ | a, |
| pcl16::PointXYZ | b | ||
| ) | [inline, static] |
Definition at line 238 of file point_cloud_segmentation.h.
| sensor_msgs::CameraInfo tabletop_pushing::PointCloudSegmentation::cam_info_ |
Definition at line 356 of file point_cloud_segmentation.h.
Definition at line 348 of file point_cloud_segmentation.h.
Definition at line 352 of file point_cloud_segmentation.h.
Definition at line 347 of file point_cloud_segmentation.h.
Definition at line 338 of file point_cloud_segmentation.h.
Definition at line 357 of file point_cloud_segmentation.h.
Definition at line 367 of file point_cloud_segmentation.h.
Definition at line 366 of file point_cloud_segmentation.h.
Definition at line 353 of file point_cloud_segmentation.h.
Definition at line 361 of file point_cloud_segmentation.h.
Definition at line 359 of file point_cloud_segmentation.h.
Definition at line 362 of file point_cloud_segmentation.h.
Definition at line 360 of file point_cloud_segmentation.h.
Definition at line 350 of file point_cloud_segmentation.h.
Definition at line 340 of file point_cloud_segmentation.h.
Definition at line 342 of file point_cloud_segmentation.h.
Definition at line 344 of file point_cloud_segmentation.h.
Definition at line 349 of file point_cloud_segmentation.h.
Definition at line 339 of file point_cloud_segmentation.h.
Definition at line 341 of file point_cloud_segmentation.h.
Definition at line 343 of file point_cloud_segmentation.h.
Definition at line 358 of file point_cloud_segmentation.h.
Definition at line 364 of file point_cloud_segmentation.h.
Definition at line 365 of file point_cloud_segmentation.h.
Definition at line 363 of file point_cloud_segmentation.h.
Definition at line 355 of file point_cloud_segmentation.h.
Definition at line 369 of file point_cloud_segmentation.h.
Definition at line 368 of file point_cloud_segmentation.h.
Eigen::Vector4f tabletop_pushing::PointCloudSegmentation::table_centroid_ [protected] |
Definition at line 335 of file point_cloud_segmentation.h.
Definition at line 346 of file point_cloud_segmentation.h.
Definition at line 345 of file point_cloud_segmentation.h.
boost::shared_ptr<tf::TransformListener> tabletop_pushing::PointCloudSegmentation::tf_ [protected] |
Definition at line 334 of file point_cloud_segmentation.h.
Definition at line 354 of file point_cloud_segmentation.h.
Definition at line 351 of file point_cloud_segmentation.h.