39 #ifndef AR_TRACK_ALVAR_KINECT_FILTERING_H 40 #define AR_TRACK_ALVAR_KINECT_FILTERING_H 43 #include <pcl/point_types.h> 44 #include <pcl/registration/icp.h> 45 #include <pcl/registration/registration.h> 47 #include <geometry_msgs/PoseStamped.h> 49 #include <pcl/ModelCoefficients.h> 50 #include <pcl/point_types.h> 51 #include <pcl/sample_consensus/method_types.h> 52 #include <pcl/sample_consensus/model_types.h> 53 #include <pcl/segmentation/sac_segmentation.h> 55 #include <pcl/filters/extract_indices.h> 56 #include <boost/lexical_cast.hpp> 57 #include <Eigen/StdVector> 59 #include <opencv2/core/core.hpp> 72 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
80 const std::vector<cv::Point, Eigen::aligned_allocator<cv::Point> >& pixels);
92 const ARPoint& p1,
const ARPoint& p2,
93 const ARPoint& p3,
const ARPoint& p4,
94 geometry_msgs::Quaternion &retQ);
99 const ARPoint& p1,
const ARPoint& p2,
100 const ARPoint& p3,
const ARPoint& p4,
105 geometry_msgs::Point
centroid (
const ARCloud& points);
108 #endif // include guard
pcl::PointCloud< ARPoint > ARCloud
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PlaneFitResult()
int extractOrientation(const pcl::ModelCoefficients &coeffs, const ARPoint &p1, const ARPoint &p2, const ARPoint &p3, const ARPoint &p4, geometry_msgs::Quaternion &retQ)
ARCloud::Ptr filterCloud(const ARCloud &cloud, const std::vector< cv::Point, Eigen::aligned_allocator< cv::Point > > &pixels)
geometry_msgs::Point centroid(const ARCloud &points)
int extractFrame(const pcl::ModelCoefficients &coeffs, const ARPoint &p1, const ARPoint &p2, const ARPoint &p3, const ARPoint &p4, tf::Matrix3x3 &retmat)
pcl::ModelCoefficients coeffs
PlaneFitResult fitPlane(ARCloud::ConstPtr cloud)