finger_hand.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 FINGER_HAND_H
00033 #define FINGER_HAND_H
00034 
00035 #include <Eigen/Dense>
00036 #include <iostream>
00037 #include <vector>
00038 
00048 class FingerHand
00049 {
00050 public:
00051 
00055   FingerHand()
00056   {
00057   }
00058         
00065   FingerHand(double finger_width, double hand_outer_diameter, double hand_depth);
00066 
00071   void evaluateFingers(double bite);
00072         
00076   void evaluateHand();
00077         
00086   void evaluateGraspParameters(double bite);
00087         
00093   void deepenHand(double init_deepness, double max_deepness);
00094         
00103   void setPoints(const Eigen::MatrixXd& points)
00104   {
00105     this->points_ = points;
00106   }
00107         
00112   double getHandDepth() const
00113   {
00114     return hand_depth_;
00115   }
00116         
00121   const Eigen::Array<bool, 1, Eigen::Dynamic>& getHand() const
00122   {
00123     return hand_;
00124   }
00125         
00130   const Eigen::Array<bool, 1, Eigen::Dynamic>& getFingers() const
00131   {
00132     return fingers_;
00133   }
00134         
00139   const Eigen::Vector2d& getGraspBottom() const
00140   {
00141     return grasp_bottom;
00142   }
00143         
00148   const Eigen::Vector2d& getGraspSurface() const
00149   {
00150     return grasp_surface;
00151   }
00152         
00157   double getGraspWidth() const
00158   {
00159     return grasp_width_;
00160   }
00161         
00166   double getBackOfHand() const
00167   {
00168     return back_of_hand_;
00169   }
00170 
00171 private:
00172 
00173   double finger_width_; 
00174   double hand_outer_diameter_; 
00175   double hand_depth_; 
00176 
00177   double back_of_hand_; 
00178 
00179   double grasp_width_; 
00180 
00181   Eigen::VectorXd finger_spacing_; 
00182   Eigen::Array<bool, 1, Eigen::Dynamic> fingers_; 
00183   Eigen::Array<bool, 1, Eigen::Dynamic> hand_;
00184   Eigen::MatrixXd points_; 
00185   Eigen::Vector2d grasp_bottom; 
00186   Eigen::Vector2d grasp_surface; 
00187 };
00188 
00189 #endif


agile_grasp
Author(s):
autogenerated on Thu Aug 27 2015 12:01:28