kinect_filtering.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  */
30 
39 #ifndef AR_TRACK_ALVAR_KINECT_FILTERING_H
40 #define AR_TRACK_ALVAR_KINECT_FILTERING_H
41 
43 #include <pcl/point_types.h>
44 #include <pcl/registration/icp.h>
45 #include <pcl/registration/registration.h>
46 
47 #include <geometry_msgs/PoseStamped.h>
48 #include <ros/ros.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>
54 #include <pcl_ros/point_cloud.h>
55 #include <pcl/filters/extract_indices.h>
56 #include <boost/lexical_cast.hpp>
57 #include <Eigen/StdVector>
58 
59 #include <opencv2/core/core.hpp>
60 
62 
63 namespace ar_track_alvar
64 {
65 
66 typedef pcl::PointXYZRGB ARPoint;
67 typedef pcl::PointCloud<ARPoint> ARCloud;
68 
69 // Result of plane fit: inliers and the plane equation
71 {
72  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
73  PlaneFitResult () : inliers(ARCloud::Ptr(new ARCloud)) {}
74  ARCloud::Ptr inliers;
75  pcl::ModelCoefficients coeffs;
76 };
77 
78 // Select out a subset of a cloud corresponding to a set of pixel coordinates
79 ARCloud::Ptr filterCloud (const ARCloud& cloud,
80  const std::vector<cv::Point, Eigen::aligned_allocator<cv::Point> >& pixels);
81 
82 // Wrapper for PCL plane fitting
83 PlaneFitResult fitPlane (ARCloud::ConstPtr cloud);
84 
85 // Given the coefficients of a plane, and two points p1 and p2, we produce a
86 // quaternion q that sends p2'-p1' to (1,0,0) and n to (0,0,1), where p1' and
87 // p2' are the projections of p1 and p2 onto the plane and n is the normal.
88 // There's a sign ambiguity here, which is resolved by requiring that the
89 // difference p4'-p3' ends up with a positive y coordinate
90 int
91 extractOrientation (const pcl::ModelCoefficients& coeffs,
92  const ARPoint& p1, const ARPoint& p2,
93  const ARPoint& p3, const ARPoint& p4,
94  geometry_msgs::Quaternion &retQ);
95 
96 // Like extractOrientation except return value is a btMatrix3x3
97 int
98 extractFrame (const pcl::ModelCoefficients& coeffs,
99  const ARPoint& p1, const ARPoint& p2,
100  const ARPoint& p3, const ARPoint& p4,
101  tf::Matrix3x3 &retmat);
102 
103 
104 // Return the centroid (mean) of a point cloud
105 geometry_msgs::Point centroid (const ARCloud& points);
106 } // namespace
107 
108 #endif // include guard
pcl::PointXYZRGB ARPoint
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)


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Mon Jun 10 2019 12:47:04