kinect_filtering.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  */
00030 
00039 #ifndef AR_TRACK_ALVAR_KINECT_FILTERING_H
00040 #define AR_TRACK_ALVAR_KINECT_FILTERING_H
00041 
00042 #include <pcl/ros/conversions.h>
00043 #include <pcl/point_types.h>
00044 #include <pcl/registration/icp.h>
00045 #include <pcl/registration/registration.h>
00046 
00047 #include <geometry_msgs/PoseStamped.h>
00048 #include <ros/ros.h>
00049 #include <pcl/ModelCoefficients.h>
00050 #include <pcl/point_types.h>
00051 #include <pcl/sample_consensus/method_types.h>
00052 #include <pcl/sample_consensus/model_types.h>
00053 #include <pcl/segmentation/sac_segmentation.h>
00054 #include <pcl_ros/point_cloud.h>
00055 #include <pcl/filters/extract_indices.h>
00056 #include <boost/lexical_cast.hpp>
00057 
00058 #include <opencv2/core/core.hpp>
00059 
00060 #include <LinearMath/btMatrix3x3.h>
00061 
00062 namespace ar_track_alvar
00063 {
00064 
00065 typedef pcl::PointXYZRGB ARPoint;
00066 typedef pcl::PointCloud<ARPoint> ARCloud;
00067 
00068 // Result of plane fit: inliers and the plane equation
00069 struct PlaneFitResult
00070 {
00071   EIGEN_MAKE_ALIGNED_OPERATOR_NEW  
00072   PlaneFitResult () : inliers(boost::make_shared<ARCloud>()) {}
00073   ARCloud::Ptr inliers;
00074   pcl::ModelCoefficients coeffs;
00075 };
00076 
00077 // Select out a subset of a cloud corresponding to a set of pixel coordinates
00078 ARCloud::Ptr filterCloud (const ARCloud& cloud,
00079                           const std::vector<cv::Point>& pixels);
00080 
00081 // Wrapper for PCL plane fitting
00082 PlaneFitResult fitPlane (ARCloud::ConstPtr cloud);
00083 
00084 // Given the coefficients of a plane, and two points p1 and p2, we produce a 
00085 // quaternion q that sends p2'-p1' to (1,0,0) and n to (0,0,1), where p1' and
00086 // p2' are the projections of p1 and p2 onto the plane and n is the normal. 
00087 // There's a sign ambiguity here, which is resolved by requiring that the
00088 // difference p4'-p3' ends up with a positive y coordinate
00089 int
00090 extractOrientation (const pcl::ModelCoefficients& coeffs,
00091                     const ARPoint& p1, const ARPoint& p2,
00092                     const ARPoint& p3, const ARPoint& p4,
00093                     geometry_msgs::Quaternion &retQ);
00094 
00095 // Like extractOrientation except return value is a btMatrix3x3
00096 int
00097 extractFrame (const pcl::ModelCoefficients& coeffs,
00098               const ARPoint& p1, const ARPoint& p2,
00099               const ARPoint& p3, const ARPoint& p4,
00100               btMatrix3x3 &retmat);
00101 
00102 
00103 // Return the centroid (mean) of a point cloud
00104 geometry_msgs::Point centroid (const ARCloud& points);
00105 } // namespace
00106 
00107 #endif // include guard


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Sun Oct 5 2014 22:16:26