footstep_state.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, 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_FOOTSTEP_PLANNER_FOOTSTEP_STATE_H_
00038 #define JSK_FOOTSTEP_PLANNER_FOOTSTEP_STATE_H_
00039 
00040 #include <jsk_footstep_msgs/Footstep.h>
00041 
00042 #include <pcl/kdtree/kdtree_flann.h>
00043 #include <pcl/filters/crop_box.h>
00044 #include <pcl/sample_consensus/method_types.h>
00045 #include <pcl/sample_consensus/model_types.h>
00046 #include <pcl/segmentation/sac_segmentation.h>
00047 #include <pcl/segmentation/sac_segmentation.h>
00048 #include <pcl/filters/project_inliers.h>
00049 #include <pcl/search/octree.h>
00050 
00051 #include "jsk_footstep_planner/ann_grid.h"
00052 #include "jsk_footstep_planner/util.h"
00053 namespace jsk_footstep_planner
00054 {
00055 
00056   namespace projection_state
00057   {
00058     const unsigned int success = 1;
00059     const unsigned int no_pointcloud = 2;
00060     const unsigned int no_enough_support = 4;
00061     const unsigned int no_plane = 8;
00062     const unsigned int no_enough_inliers = 16;
00063     const unsigned int close_to_success = 32;
00064     const unsigned int transition_limit = 64;
00065     const unsigned int vertical_footstep = 128;
00066   }
00067 
00068   std::string projectStateToString(unsigned int state);
00069   
00070   enum FootstepSupportState
00071   {
00072     NOT_SUPPORTED,
00073     SUPPORTED,
00074     CLOSE_TO_SUPPORTED,
00075   };
00076   
00077   class FootstepState
00078   {
00079   public:
00080     typedef boost::shared_ptr<FootstepState> Ptr;
00081     FootstepState(int leg,
00082                   const Eigen::Affine3f& pose,
00083                   const Eigen::Vector3f& dimensions,
00084                   const Eigen::Vector3f& resolution):
00085       leg_(leg), pose_(pose), dimensions_(dimensions), resolution_(resolution)
00086     {
00087       float x = pose_.translation()[0];
00088       float y = pose_.translation()[1];
00089       float roll, pitch, yaw;
00090       pcl::getEulerAngles(pose_, roll, pitch, yaw);
00091       index_x_ = x / resolution_[0];
00092       index_y_ = y / resolution_[1];
00093       index_yaw_ = yaw / resolution_[2];
00094     }
00095 
00096     FootstepState(int leg,
00097                   const Eigen::Affine3f& pose,
00098                   const Eigen::Vector3f& dimensions,
00099                   const Eigen::Vector3f& resolution,
00100                   int index_x,
00101                   int index_y,
00102                   int index_yaw):
00103       leg_(leg), pose_(pose), dimensions_(dimensions), resolution_(resolution),
00104       index_x_(index_x), index_y_(index_y), index_yaw_(index_yaw)
00105     {
00106     }
00107 
00108     static
00109     FootstepState::Ptr fromROSMsg(const jsk_footstep_msgs::Footstep& f,
00110                                   const Eigen::Vector3f& size,
00111                                   const Eigen::Vector3f& resolution);
00112     
00113     inline float cross2d(const Eigen::Vector2f& a, const Eigen::Vector2f& b) const
00114     {
00115       return a[0] * b[1] - a[1] * b[0];
00116     }
00117     virtual jsk_footstep_msgs::Footstep::Ptr toROSMsg();
00118     virtual FootstepState::Ptr
00119     projectToCloud(pcl::KdTreeFLANN<pcl::PointNormal>& tree,
00120                    pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00121                    ANNGrid::Ptr grid_search,
00122                    pcl::search::Octree<pcl::PointNormal>& tree_2d,
00123                    pcl::PointCloud<pcl::PointNormal>::Ptr cloud_2d,
00124                    const Eigen::Vector3f& z,
00125                    unsigned int& error_state,
00126                    double outlier_threshold,
00127                    int max_iterations,
00128                    int min_inliers,
00129                    int foot_x_sampling_num = 3,
00130                    int foot_y_sampling_num = 3,
00131                    double vertex_threshold = 0.02,
00132                    const bool skip_cropping = true);
00133     
00134     pcl::PointIndices::Ptr
00135     cropPointCloud(pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00136                    pcl::search::Octree<pcl::PointNormal>& tree);
00137 
00138     pcl::PointIndices::Ptr
00139     cropPointCloud(pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00140                    ANNGrid::Ptr grid_search);
00141 
00142     pcl::PointIndices::Ptr
00143     cropPointCloudExact(pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00144                         pcl::PointIndices::Ptr near_indices);
00145 
00146     template <class PointT>
00147     PointT toPoint()
00148     {
00149       PointT p;
00150       p.getVector3fMap() = Eigen::Vector3f(pose_.translation());
00151       return p;
00152     }
00153 
00154     inline void vertices(Eigen::Vector3f& a,
00155                          Eigen::Vector3f& b,
00156                          Eigen::Vector3f& c,
00157                          Eigen::Vector3f& d)
00158     {
00159       const Eigen::Vector3f ux = Eigen::Vector3f::UnitX();
00160       const Eigen::Vector3f uy = Eigen::Vector3f::UnitY();
00161 
00162       a = Eigen::Vector3f((pose_ * Eigen::Translation3f(ux * dimensions_[0] / 2 + uy * dimensions_[1] / 2)).translation());
00163       b = Eigen::Vector3f((pose_ * Eigen::Translation3f(- ux * dimensions_[0] / 2 + uy * dimensions_[1] / 2)).translation());
00164       c = Eigen::Vector3f((pose_ * Eigen::Translation3f(- ux * dimensions_[0] / 2 - uy * dimensions_[1] / 2)).translation());
00165       d = Eigen::Vector3f((pose_ * Eigen::Translation3f(ux * dimensions_[0] / 2 - uy * dimensions_[1] / 2)).translation());
00166 
00167     }
00168     
00173     virtual bool crossCheck(FootstepState::Ptr other);
00174     
00175     virtual Eigen::Affine3f getPose() { return pose_; }
00176     virtual void setPose(const Eigen::Affine3f& pose)
00177     {
00178       pose_ = pose;
00179     }
00180     
00181     virtual int getLeg() { return leg_; }
00182     virtual Eigen::Vector3f getDimensions() { return dimensions_; }
00183     bool operator==(FootstepState& other)
00184     {
00185       return ((index_x_ == other.index_x_) &&
00186               (index_y_ == other.index_y_) &&
00187               (index_yaw_ == other.index_yaw_));
00188     }
00189 
00190     virtual Eigen::Vector3f getResolution() { return resolution_; }
00191       
00192 
00193     inline virtual int indexX() { return index_x_; }
00194     inline virtual int indexY() { return index_y_; }
00195     inline virtual int indexT() { return index_yaw_; }
00196 
00197 
00198     virtual FootstepSupportState
00199     isSupportedByPointCloud(const Eigen::Affine3f& pose,
00200                             pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00201                             pcl::KdTreeFLANN<pcl::PointNormal>& tree,
00202                             pcl::PointIndices::Ptr inliers,
00203                             const int foot_x_sampling_num,
00204                             const int foot_y_sampling_num,
00205                             const double vertex_threshold);
00206     virtual FootstepSupportState
00207     isSupportedByPointCloudWithoutCropping(const Eigen::Affine3f& pose,
00208                                            pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00209                                            pcl::KdTreeFLANN<pcl::PointNormal>& tree,
00210                                            pcl::PointIndices::Ptr inliers,
00211                                            const int foot_x_sampling_num,
00212                                            const int foot_y_sampling_num,
00213                                            const double vertex_threshold);
00214 
00215   protected:
00216     Eigen::Affine3f pose_;
00217     const Eigen::Vector3f dimensions_;
00218     const Eigen::Vector3f resolution_; // not memory efficient?
00219     const int leg_;
00220     int index_x_;
00221     int index_y_;
00222     int index_yaw_;
00223   private:
00224     
00225   };
00226 
00227   inline size_t hash_value(const FootstepState::Ptr& s)
00228   {
00229     return std::abs(s->indexX()) << (25 + 14) + std::abs(s->indexY()) << 14
00230       + std::abs(s->indexT());
00231   }
00232   
00233 }
00234 
00235 #endif


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:37:57