grasp_hypothesis.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, Andreas ten Pas
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *
00018  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00019  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00020  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00021  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00022  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00023  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00026  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00027  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00028  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  *  POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 #ifndef GRASP_HYPOTHESIS_H_
00033 #define GRASP_HYPOTHESIS_H_
00034 
00035 #include <Eigen/Dense>
00036 #include <iostream>
00037 #include <vector>
00038 
00046 class GraspHypothesis
00047 {
00048 public:
00049 
00053         GraspHypothesis() : cam_source_(-1) {}
00054 
00067         GraspHypothesis(const Eigen::Vector3d& axis, const Eigen::Vector3d& approach,
00068                 const Eigen::Vector3d& binormal, const Eigen::Vector3d& bottom, const Eigen::Vector3d& surface,
00069                 double width, const Eigen::Matrix3Xd& points_for_learning, const std::vector<int>& indices_cam1,
00070                 const std::vector<int>& indices_cam2, int cam_source) :
00071                         axis_(axis), approach_(approach), binormal_(binormal), grasp_bottom_(bottom), grasp_surface_(surface),
00072                                 grasp_width_(width), points_for_learning_(points_for_learning),
00073                                 indices_points_for_learning_cam1_(indices_cam1), indices_points_for_learning_cam2_(indices_cam2),
00074                                 cam_source_(cam_source), half_antipodal_(false), full_antipodal_(false)
00075         {       }
00076         
00080         void print();
00081         
00086         const Eigen::Vector3d& getApproach() const
00087         {
00088                 return approach_;
00089         }
00090         
00095         const Eigen::Vector3d& getAxis() const
00096         {
00097                 return axis_;
00098         }
00099         
00104         const Eigen::Vector3d& getBinormal() const
00105         {
00106                 return binormal_;
00107         }
00108         
00113         bool isFullAntipodal() const
00114         {
00115                 return full_antipodal_;
00116         }
00117         
00122         const Eigen::Vector3d& getGraspBottom() const
00123         {
00124                 return grasp_bottom_;
00125         }
00126 
00131         const Eigen::Vector3d& getGraspSurface() const
00132         {
00133                 return grasp_surface_;
00134         }
00135         
00140         double getGraspWidth() const
00141         {
00142                 return grasp_width_;
00143         }
00144         
00149         bool isHalfAntipodal() const
00150         {
00151                 return half_antipodal_;
00152         }
00153         
00158         const std::vector<int>& getIndicesPointsForLearningCam1() const
00159         {
00160                 return indices_points_for_learning_cam1_;
00161         }
00162         
00167         const std::vector<int>& getIndicesPointsForLearningCam2() const
00168         {
00169                 return indices_points_for_learning_cam2_;
00170         }
00171         
00176         const Eigen::Matrix3Xd& getPointsForLearning() const
00177         {
00178                 return points_for_learning_;
00179         }
00180         
00185         int getCamSource() const
00186         {
00187                 return cam_source_;
00188         }
00189 
00194         void setFullAntipodal(bool b)
00195         {
00196                 full_antipodal_ = b;
00197         }
00198         
00203         void setHalfAntipodal(bool b)
00204         {
00205                 half_antipodal_ = b;
00206         }
00207         
00212         void setGraspWidth(double w)
00213         {
00214                 grasp_width_ = w;
00215         }
00216 
00217 private:
00218 
00219         int cam_source_; 
00220         Eigen::Matrix3Xd points_for_learning_; 
00221         std::vector<int> indices_points_for_learning_cam1_; 
00222         std::vector<int> indices_points_for_learning_cam2_; 
00223         Eigen::Vector3d axis_; 
00224         Eigen::Vector3d approach_; 
00225         Eigen::Vector3d binormal_; 
00226         Eigen::Vector3d grasp_bottom_; 
00227         Eigen::Vector3d grasp_surface_; 
00228         double grasp_width_; 
00229         bool full_antipodal_; 
00230         bool half_antipodal_; 
00231 };
00232 
00233 #endif /* GRASP_HYPOTHESIS_H_ */


agile_grasp
Author(s): Andreas ten Pas
autogenerated on Sat Jun 8 2019 20:08:27