edgebased_cube_finder.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 
00037 #ifndef JSK_PCL_ROS_EDGE_BASED_CUBE_FINDER_H_
00038 #define JSK_PCL_ROS_EDGE_BASED_CUBE_FINDER_H_
00039 
00040 #include <pcl_ros/pcl_nodelet.h>
00041 
00043 // messages
00045 #include <sensor_msgs/PointCloud2.h>
00046 #include <jsk_recognition_msgs/ParallelEdge.h>
00047 #include <jsk_recognition_msgs/PolygonArray.h>
00048 #include <jsk_recognition_msgs/BoundingBoxArray.h>
00049 #include <jsk_recognition_msgs/ParallelEdgeArray.h>
00050 
00051 #include "jsk_recognition_utils/geo_util.h"
00052 #include "jsk_recognition_utils/pcl_conversion_util.h"
00053 #include "jsk_recognition_utils/pcl_util.h"
00054 
00055 #include <message_filters/subscriber.h>
00056 #include <message_filters/time_synchronizer.h>
00057 #include <message_filters/synchronizer.h>
00058 
00059 #include <boost/tuple/tuple.hpp>
00060 #include <jsk_pcl_ros/EdgebasedCubeFinderConfig.h>
00061 #include <dynamic_reconfigure/server.h>
00062 
00063 #include <jsk_topic_tools/connection_based_nodelet.h>
00064 
00065 namespace jsk_pcl_ros
00066 {
00067   typedef boost::tuple<pcl::PointIndices::Ptr, pcl::PointIndices::Ptr>
00068   IndicesPair;
00069   typedef boost::tuple<pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr>
00070   CoefficientsPair;
00071 
00072   typedef boost::tuple<pcl::PointIndices::Ptr, pcl::PointIndices::Ptr, pcl::PointIndices::Ptr>
00073   IndicesTriple;
00074   typedef boost::tuple<pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr>
00075   CoefficientsTriple;
00076   typedef boost::tuple<IndicesTriple, CoefficientsTriple>
00077   IndicesCoefficientsTriple;
00078   
00080   // class to represent a hypothesis
00081   //   value_ := 0.0 ~ 1.0
00083   class CubeHypothesis
00084   {
00085   public:
00086     typedef boost::shared_ptr<CubeHypothesis> Ptr;
00087     CubeHypothesis(const IndicesPair& pair,
00088                    const CoefficientsPair& coefficients_pair,
00089                    const double outlier_threshold);
00090     virtual ~CubeHypothesis();
00091     virtual double getValue() { return value_; };
00092     virtual jsk_recognition_utils::Cube::Ptr getCube() { return cube_; };
00093     virtual void estimate(const pcl::PointCloud<pcl::PointXYZRGB>& cloud) = 0;
00094     
00095     virtual double evaluatePointOnPlanes(
00096       const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
00097       jsk_recognition_utils::ConvexPolygon& polygon_a,
00098       jsk_recognition_utils::ConvexPolygon& polygon_b);
00099     virtual jsk_recognition_utils::PointPair computeAxisEndPoints(
00100       const jsk_recognition_utils::Line& axis,
00101       const jsk_recognition_utils::PointPair& a_candidates,
00102       const jsk_recognition_utils::PointPair& b_candidates);
00103   protected:
00105     // methods
00107     virtual void computeCentroid(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& cloud,
00108                                  const pcl::PointIndices::Ptr& indices,
00109                                  Eigen::Vector3f& output);
00110     virtual void getLinePoints(const jsk_recognition_utils::Line& line,
00111                                const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
00112                                const pcl::PointIndices::Ptr indices,
00113                                jsk_recognition_utils::Vertices& output);
00114     virtual jsk_recognition_utils::ConvexPolygon::Ptr buildConvexPolygon(
00115       const jsk_recognition_utils::PointPair& a_edge_pair, const jsk_recognition_utils::PointPair& b_edge_pair);
00116     
00118     // variables
00120     double value_;
00121     const IndicesPair indices_pair_;
00122     const CoefficientsPair coefficients_pair_;
00123     double outlier_threshold_;
00124     jsk_recognition_utils::Cube::Ptr cube_;
00125   private:
00126   };
00127 
00128   class PlanarCubeHypothesis: public CubeHypothesis
00129   {
00130   public:
00131     typedef boost::shared_ptr<PlanarCubeHypothesis> Ptr;
00132     PlanarCubeHypothesis(const IndicesPair& pair,
00133                          const CoefficientsPair& coefficients_pair,
00134                          const double outlier_threshold);
00135     virtual void estimate(const pcl::PointCloud<pcl::PointXYZRGB>& cloud)
00136     {
00137     }
00138     
00139   protected:
00140   private:
00141   };
00142   
00143   class DiagnoalCubeHypothesis: public CubeHypothesis
00144   {
00145   public:
00146     typedef boost::shared_ptr<DiagnoalCubeHypothesis> Ptr;
00147     DiagnoalCubeHypothesis(const IndicesPair& pair,
00148                            const CoefficientsPair& coefficients_pair,
00149                            const double outlier_threshold);
00150     virtual void estimate(const pcl::PointCloud<pcl::PointXYZRGB>& cloud);
00151   protected:
00152     int resolution_;
00153     double min_angle_;
00154   private:
00155   };
00156   
00157   class EdgebasedCubeFinder: public jsk_topic_tools::ConnectionBasedNodelet
00158   {
00159   public:
00160     typedef message_filters::sync_policies::ExactTime<
00161     sensor_msgs::PointCloud2,
00162     jsk_recognition_msgs::ParallelEdgeArray > SyncPolicy;
00163     typedef pcl::PointXYZRGB PointT;
00164     typedef jsk_pcl_ros::EdgebasedCubeFinderConfig Config;
00165     enum EdgeRelation
00166     {
00167       NOT_PERPENDICULAR,
00168       A_PERPENDICULAR,
00169       B_PERPENDICULAR,
00170       C_PERPENDICULAR
00171     };
00172     
00173   protected:
00174     
00175     
00177     // methods
00179     virtual void onInit();
00180     
00181     virtual void estimate(
00182       const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
00183       const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges);
00184     virtual void estimate2(
00185       const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
00186       const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges);
00187 
00189     // combinateIndices
00190     //   indices := list of pcl::PointIndices. the length of the
00191     //              list should be greater equal than 2.
00193     virtual std::vector<IndicesPair> combinateIndices(
00194       const std::vector<pcl::PointIndices::Ptr>& indices);
00195 
00196     virtual std::vector<CoefficientsPair> combinateCoefficients(
00197       const std::vector<pcl::ModelCoefficients::Ptr>& coefficients);
00198     
00199     virtual bool isPerpendicularVector(
00200       const Eigen::Vector3f& a,
00201       const Eigen::Vector3f& b);
00202     
00203     virtual std::vector<IndicesCoefficientsTriple>
00204     tripleIndicesAndCoefficients(
00205       const std::vector<pcl::PointIndices::Ptr>& indices,
00206       const std::vector<pcl::ModelCoefficients::Ptr>& coefficients);
00207 
00208     virtual EdgeRelation perpendicularEdgeTriple(
00209       const jsk_recognition_utils::Line& edge_a,
00210       const jsk_recognition_utils::Line& edge_b,
00211       const jsk_recognition_utils::Line& edge_c);
00212     
00213     
00214     virtual std::vector<IndicesCoefficientsTriple>
00215     filterPerpendicularEdgeTriples(
00216       const std::vector<IndicesCoefficientsTriple>& triples);
00217 
00218     virtual jsk_recognition_utils::Line::Ptr midLineFromCoefficientsPair(
00219       const CoefficientsPair& pair);
00220 
00221     virtual jsk_recognition_utils::ConvexPolygon::Ptr convexFromPairs(
00222       const pcl::PointCloud<PointT>::Ptr cloud,
00223       const CoefficientsPair& coefficients_pair,
00224       const IndicesPair& indices_pair);
00225     virtual int countInliers(
00226       const pcl::PointCloud<PointT>::Ptr cloud,
00227       const jsk_recognition_utils::ConvexPolygon::Ptr convex);
00228     virtual void filterBasedOnConvex(
00229       const pcl::PointCloud<PointT>::Ptr cloud,
00230       const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes,
00231       std::vector<int>& output_indices);
00232     virtual void filterPairsBasedOnParallelEdgeDistances(
00233       const std::vector<IndicesPair>& pairs,
00234       const std::vector<CoefficientsPair>& coefficients_pair,
00235       std::vector<IndicesPair>& filtered_indices_pairs,
00236       std::vector<CoefficientsPair>& filtered_coefficients_pairs);
00237 
00238     virtual jsk_recognition_utils::Cube::Ptr cubeFromIndicesAndCoefficients(
00239     const pcl::PointCloud<PointT>::Ptr cloud,
00240     const IndicesCoefficientsTriple& indices_coefficients_triple,
00241     pcl::PointCloud<EdgebasedCubeFinder::PointT>::Ptr points_on_edge);
00242     
00243     virtual pcl::PointCloud<PointT>::Ptr extractPointCloud(
00244       const pcl::PointCloud<PointT>::Ptr cloud,
00245       const pcl::PointIndices::Ptr indices);
00246     
00247     virtual jsk_recognition_utils::PointPair minMaxPointOnLine(
00248       const jsk_recognition_utils::Line& line,
00249       const pcl::PointCloud<PointT>::Ptr cloud);
00250     
00251     virtual void estimateParallelPlane(
00252       const jsk_recognition_utils::ConvexPolygon::Ptr convex,
00253       const pcl::PointCloud<PointT>::Ptr filtered_cloud,
00254       pcl::PointIndices::Ptr output_inliers,
00255       pcl::ModelCoefficients::Ptr output_coefficients);
00256 
00257     virtual void estimatePerpendicularPlane(
00258      const jsk_recognition_utils::ConvexPolygon::Ptr convex,
00259      const CoefficientsPair& edge_coefficients,
00260      const pcl::PointCloud<PointT>::Ptr filtered_cloud,
00261      pcl::PointIndices::Ptr output_inliers,
00262      pcl::ModelCoefficients::Ptr output_coefficients);
00263     
00264     //virtual pcl::PointCloud<EdgebasedCubeFinder::PointT>::Ptr
00265     virtual pcl::PointIndices::Ptr
00266     preparePointCloudForRANSAC(
00267       const jsk_recognition_utils::ConvexPolygon::Ptr convex,
00268       const CoefficientsPair& edge_coefficients_pair,
00269       const pcl::PointCloud<PointT>::Ptr cloud);
00270 
00271     virtual jsk_recognition_utils::ConvexPolygon::Ptr
00272     estimateConvexPolygon(
00273       const pcl::PointCloud<PointT>::Ptr cloud,
00274       const pcl::PointIndices::Ptr indices,
00275       pcl::ModelCoefficients::Ptr coefficients,
00276       pcl::PointIndices::Ptr inliers);
00277     
00278     virtual void configCallback (Config &config, uint32_t level);
00279 
00280     virtual void subscribe();
00281     virtual void unsubscribe();
00283     // ROS variables
00285     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00286     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00287     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00288     message_filters::Subscriber<jsk_recognition_msgs::ParallelEdgeArray> sub_edges_;
00289     ros::Publisher pub_;
00290     ros::Publisher pub_pose_array_;
00291     ros::Publisher pub_debug_marker_, pub_debug_filtered_cloud_,
00292       pub_debug_polygons_, pub_debug_clusers_;
00293     boost::mutex mutex_;
00295     // parameters for cube finnding
00297     double outlier_threshold_;
00298     double min_inliers_;
00299     double convex_area_threshold_;
00300     double convex_edge_threshold_;
00301     double parallel_edge_distance_min_threshold_, parallel_edge_distance_max_threshold_;
00302   private:
00303     
00304   };
00305 }
00306 
00307 #endif


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:49