hand.h

Go to the documentation of this file.
00001 /***************************************************************************
00002  *   Copyright (C) 2005-2011 LpzRobots development team                    *
00003  *    Georg Martius  <georg dot martius at web dot de>                     *
00004  *    Frank Guettler <guettler at informatik dot uni-leipzig dot de        *
00005  *    Frank Hesse    <frank at nld dot ds dot mpg dot de>                  *
00006  *    Ralf Der       <ralfder at mis dot mpg dot de>                       *
00007  *                                                                         *
00008  *   This program is free software; you can redistribute it and/or modify  *
00009  *   it under the terms of the GNU General Public License as published by  *
00010  *   the Free Software Foundation; either version 2 of the License, or     *
00011  *   (at your option) any later version.                                   *
00012  *                                                                         *
00013  *   This program is distributed in the hope that it will be useful,       *
00014  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00015  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
00016  *   GNU General Public License for more details.                          *
00017  *                                                                         *
00018  *   You should have received a copy of the GNU General Public License     *
00019  *   along with this program; if not, write to the                         *
00020  *   Free Software Foundation, Inc.,                                       *
00021  *   59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.             *
00022  *                                                                         *
00023  ***************************************************************************/
00024 #ifndef __HAND_H
00025 #define __HAND_H
00026 
00027 #include "oderobot.h"
00028 #include <selforg/configurable.h>
00029 #include "primitive.h"
00030 #include "joint.h"
00031 #include "angularmotor.h"
00032 #include "oneaxisservo.h"
00033 
00034 #include "primitive.h"
00035 #include "osgforwarddecl.h"
00036 #include "axis.h"
00037 
00038 #include "irsensor.h"
00039 #include "raysensorbank.h"
00040 #include "raysensor.h"
00041 
00042 namespace lpzrobots {
00043 
00044   enum Motor_type
00045     {
00046       With_servo_motor,
00047       Without_servo_motor
00048     };
00049 
00050   enum IrSensor_Type{
00051     irDrawAll,
00052     irBack,
00053     irSide,
00054     irFront
00055   };
00056 
00057   // struct containing geom and body for each beam (= box, (cappped)cylinder, sphere)
00058   typedef struct {
00059     
00060     public:
00061     double velocity;
00062     double power;       // used when non-servo motor is used
00063     double servo_motor_Power;  // used when servo motor is used
00064     bool show_contacts;
00065     enum Motor_type set_typ_of_motor;
00066     double factorSensor;
00067     bool fix_palm_joint;
00068     bool one_finger_as_one_motor;
00069     bool draw_joints;
00070     bool showFingernails;
00071     double fingerJointBendAngle;
00072     bool initWithOpenHand; // init hand with open or half closed hand
00073 
00074     //---------------InfrarRedSensor--------------------------  
00075     double irRange;
00076     bool ir_sensor_used;
00077     bool irs_at_fingertip;
00078     bool irs_at_fingertop;
00079     bool irs_at_fingercenter;
00080     bool irs_at_fingerbottom;
00081     enum RaySensor::rayDrawMode ray_draw_mode; // for possible modes see sensors/raysensor.h
00082   } HandConf;
00083 
00084   enum GripMode{
00085     lateral,
00086     precision
00087   };
00088 
00089   /**
00090    * Artificial Hand 
00091    * 
00092    */
00093   class Hand : public OdeRobot{
00094   public:
00095 
00096     /**
00097      * constructor of hand
00098      * @param odeHandle data structure for accessing ODE
00099      * @param osgHandle ata structure for accessing OSG
00100      * @param conf configuration of robot
00101      */
00102     Hand(const OdeHandle& odeHandle, const OsgHandle& osgHandle, const HandConf& conf, const std::string& name);
00103 
00104     static HandConf getDefaultConf()
00105       {
00106         HandConf conf;
00107         conf.velocity = 0.2;
00108         conf.power = 5;
00109         conf.servo_motor_Power = 0.1;
00110         conf.show_contacts = true;
00111         conf.set_typ_of_motor = Without_servo_motor;
00112         conf.irRange = 2;
00113         conf.ir_sensor_used=true;
00114         conf.irs_at_fingerbottom=true;
00115         conf.irs_at_fingercenter=true;
00116         conf.irs_at_fingertop =true;
00117         conf.irs_at_fingertip =false;
00118         conf.ray_draw_mode=RaySensor::drawAll;
00119         conf.factorSensor=1.0;
00120         conf.fix_palm_joint=true;
00121         conf.one_finger_as_one_motor=false;
00122         conf.draw_joints=false;
00123         conf.showFingernails=true;
00124         conf.fingerJointBendAngle=M_PI/2;
00125         conf.initWithOpenHand=true; // init with open hand
00126         return conf;
00127       }
00128 
00129   
00130     /** 
00131      * update the subcomponents
00132      */
00133     virtual void update();
00134 
00135     /** 
00136      * sets the pose of the vehicle
00137      * @param pose desired 4x4 pose matrix
00138      */
00139     virtual void place(const osg::Matrix& pose);
00140 
00141     /** this function is called in each timestep. It should perform robot-internal checks, 
00142         like space-internal collision detection, sensor resets/update etc.
00143         @param globalData structure that contains global data from the simulation environment
00144     */
00145     virtual void doInternalStuff(GlobalData& globalData);
00146   
00147 
00148     /** returns actual sensorvalues
00149         @param sensors sensors scaled to [-1,1] 
00150         @param sensornumber length of the sensor array
00151         @return number of actually written sensors
00152     */
00153     virtual int getSensors(sensor* sensors, int sensornumber);
00154 
00155     /** sets actual motorcommands
00156         @param motors motors scaled to [-1,1] 
00157         @param motornumber length of the motor array
00158     */
00159     virtual void setMotors(const motor* motors, int motornumber);
00160 
00161     /** returns number of sensors
00162      */
00163     virtual int getSensorNumber();
00164 
00165     /** returns number of motors
00166      */
00167     virtual int getMotorNumber();
00168 
00169     /** returns a vector with the positions of all segments of the robot
00170         @param poslist vector of positions (of all robot segments) 
00171         @return length of the list
00172     */
00173     //  virtual int getSegmentsPosition(vector<Position> &poslist);
00174   
00175     /******** CONFIGURABLE ***********/
00176     virtual void notifyOnChange(const paramkey& key);
00177 
00178 
00179   protected:
00180     /** 
00181      * Returns the palm as the main object of the robot, 
00182      * which is used for position and speed tracking.
00183      */
00184     virtual Primitive* getMainPrimitive() const {
00185       if(!objects.empty()){
00186         return (objects[0]); // returns forearm for fixation
00187         //return (objects[1]); // returns palm
00188       }else return 0;
00189     }
00190 
00191 
00192   private:
00193 
00194     /** 
00195      * creates the hand at the desired pose
00196      * @param pose 4x4 pose matrix
00197      */
00198     virtual void create(const osg::Matrix& pose); 
00199 
00200     /** 
00201      * destroys robot and space
00202      */
00203     virtual void destroy();
00204 
00205     static void mycallback(void *data, dGeomID o1, dGeomID o2);
00206        
00207     /** true if robot was created */
00208     bool created;      
00209 
00210   protected:
00211 
00212     /** configuration of hand */
00213     HandConf conf;
00214 
00215     /** vector containing OSGPrimitives */
00216     std::vector <OSGPrimitive*> osg_objects;
00217     /** vector containing Primitivesinfrared sensors */
00218     std::vector <IRSensor*> ir_sensors;
00219 
00220     /** true if contact joint is created  */
00221     bool contact_joint_created;
00222 
00223     //std::vector <HingeServo*> servos;
00224     //objects.reserve(number_beams);
00225 
00226     /** vector of the joints used in hand */
00227     
00228 
00229     /** vector of the angular motors */
00230     std::vector <AngularMotor*> frictionmotors;
00231 
00232     /** vector of the used hinge servos*/
00233     std::vector <HingeServo*> servos;
00234 
00235     /**  a collection of ir sensors */
00236     RaySensorBank irSensorBank; 
00237 
00238 
00239     /** space containing the hand */
00240     dSpaceID hand_space;     
00241 
00242     //Beam beam[number_beams]; // array of elements (rectangle and cylinders)
00243     //dJointID joint[number_joints];  // array containg "normal" joints for connecting the elementsconf
00244     //dJointID fix_joint[number_fix_joints]; //joints for keeping index, middle, ring and little finger together to achieve mor prosthetic like motion
00245 
00246     /** motorjoint for actuating the forearm_palm joint (ball joint) */
00247     AngularMotor* palm_motor_joint;
00248 
00249     /** motorjoint for actuating the palm_thumb joint (ball joint) */
00250     AngularMotor* thumb_motor_joint;
00251 
00252     /** Hinge Joint between thumb_buttom and thumb_top*/
00253     HingeJoint* thumb_bt;
00254 
00255     /** Hinge Joint between buttom, center and top part of the index finger*/
00256     Joint *palm_index, *index_bc, *index_ct;
00257 
00258     /** Hinge Joint between buttom, center and top part of the middle finger*/
00259     Joint *palm_middle, *middle_bc, *middle_ct;
00260 
00261     /** Hinge Joint between buttom, center and top part of the ring finger*/
00262     Joint *palm_ring, *ring_bc, *ring_ct;
00263 
00264     /** Hinge Joint between buttom, center and top part of the little finger*/
00265     Joint *palm_little, *little_bc, *little_ct;
00266 
00267 
00268 
00269     /** for handling lateral and precision grip modes */
00270     GripMode gripmode; 
00271 
00272 
00273 
00274     /** initial position of robot */
00275     Position initial_pos;    
00276 
00277 
00278     Pos oldp;
00279 
00280     int sensorno;
00281     int motorno;
00282     int sensor_number;
00283     paramval factorForce;
00284     paramval frictionGround;
00285     
00286     double velocity;
00287 
00288  
00289   };
00290 
00291 }
00292 
00293 #endif
00294  
Generated on Thu Jun 28 14:45:36 2012 for Robot Simulator of the Robotics Group for Self-Organization of Control by  doxygen 1.6.3