rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
scene_parsing.h
Go to the documentation of this file.
1 #ifndef _RAPID_PERCEPTION_SCENE_PARSING_H_
2 #define _RAPID_PERCEPTION_SCENE_PARSING_H_
3 
4 #include <vector>
5 
6 #include "pcl/point_cloud.h"
7 #include "pcl/point_types.h"
8 
10 #include "tf/transform_datatypes.h"
11 
12 namespace rapid {
13 namespace perception {
15  // Boundaries of the box where we should search for the primary surface.
16  double min_x;
17  double min_y;
18  double min_z;
19  double max_x;
20  double max_y;
21  double max_z;
22 };
23 
25  double distance_threshold; // Max distance from fitted plane, in meters.
26  double eps_angle; // Max angle, in radians, off +z the HSurface can be.
27 };
28 
29 struct ObjectParams {
30  double distance_threshold; // Distance to search for points to merge.
31  double point_color_threshold; // Max color difference between points.
32  double region_color_threshold; // Max color difference between clusters.
33  double min_cluster_size; // Minimum number of points per cluster.
34 };
35 
36 struct ParseParams {
40 };
41 
42 // Assumes the data is coming from a Kinect mounted on the PR2's head.
44 
45 // Parse a scene from the given point cloud, using default parameters.
46 // The point cloud must be transformed into a frame such that +z points up in
47 // the real world.
48 // Returns false if parsing failed.
49 bool ParseScene(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud,
50  const ParseParams& params, Scene* scene);
51 
52 bool ParseHSurface(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud,
53  const pcl::PointIndices::ConstPtr& indices,
54  const ParseParams& params, HSurface* surface);
55 
56 bool ParseObjects(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud,
57  const pcl::PointIndices::ConstPtr& indices,
58  const ParseParams& params, std::vector<Object>* objects);
59 
60 // A horizontal plane may cut across the entire scene, so we cluster the
61 // plane
62 // and call the largest cluster the tabletop.
63 // bool FindPrimarySurface(const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
64 // pcl::PointIndices::Ptr inliers);
65 
66 } // namespace perception
67 } // namespace rapid
68 
69 #endif // _RAPID_PERCEPTION_SCENE_PARSING_H_
bool ParseScene(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const ParseParams &params, Scene *scene)
bool ParseHSurface(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &indices, const ParseParams &params, HSurface *surface)
bool ParseObjects(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &indices, const ParseParams &params, std::vector< Object > *objects)
ParseParams Pr2Params()