1 #ifndef _RAPID_PERCEPTION_SCENE_PARSING_H_
2 #define _RAPID_PERCEPTION_SCENE_PARSING_H_
6 #include "pcl/point_cloud.h"
7 #include "pcl/point_types.h"
10 #include "tf/transform_datatypes.h"
13 namespace perception {
49 bool ParseScene(
const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud,
52 bool ParseHSurface(
const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud,
53 const pcl::PointIndices::ConstPtr& indices,
56 bool ParseObjects(
const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud,
57 const pcl::PointIndices::ConstPtr& indices,
58 const ParseParams& params, std::vector<Object>* objects);
69 #endif // _RAPID_PERCEPTION_SCENE_PARSING_H_
bool ParseScene(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const ParseParams ¶ms, Scene *scene)
double distance_threshold
double region_color_threshold
bool ParseHSurface(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &indices, const ParseParams ¶ms, HSurface *surface)
double point_color_threshold
bool ParseObjects(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &indices, const ParseParams ¶ms, std::vector< Object > *objects)
double distance_threshold