00001 /*************************************************************************** 00002 * Copyright (C) 2005 by Robot Group Leipzig * 00003 * martius@informatik.uni-leipzig.de * 00004 * fhesse@informatik.uni-leipzig.de * 00005 * der@informatik.uni-leipzig.de * 00006 * * 00007 * This program is free software; you can redistribute it and/or modify * 00008 * it under the terms of the GNU General Public License as published by * 00009 * the Free Software Foundation; either version 2 of the License, or * 00010 * (at your option) any later version. * 00011 * * 00012 * This program is distributed in the hope that it will be useful, * 00013 * but WITHOUT ANY WARRANTY; without even the implied warranty of * 00014 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * 00015 * GNU General Public License for more details. * 00016 * * 00017 * You should have received a copy of the GNU General Public License * 00018 * along with this program; if not, write to the * 00019 * Free Software Foundation, Inc., * 00020 * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. * 00021 * * 00022 * $Log: muscledarm.h,v $ 00023 * Revision 1.1.4.12 2006/03/31 16:13:59 fhesse 00024 * *** empty log message *** 00025 * 00026 * Revision 1.1.4.11 2006/03/30 12:34:56 martius 00027 * documentation updated 00028 * 00029 * Revision 1.1.4.10 2006/03/28 14:24:37 fhesse 00030 * minor changes 00031 * 00032 * Revision 1.1.4.9 2006/01/31 09:58:11 fhesse 00033 * basically working now 00034 * 00035 * Revision 1.1.4.8 2006/01/13 12:22:07 fhesse 00036 * partially working 00037 * 00038 * Revision 1.1.4.7 2006/01/10 16:45:53 fhesse 00039 * not working osg version 00040 * 00041 * Revision 1.1.4.6 2006/01/10 09:38:00 fhesse 00042 * partially moved to osg 00043 * 00044 * Revision 1.1.4.5 2005/12/16 16:36:05 fhesse 00045 * manual control via keyboard 00046 * setMotors via dJointAddSliderForce 00047 * 00048 * Revision 1.1.4.4 2005/11/24 16:15:57 fhesse 00049 * moved from main branch, sensors improved 00050 * 00051 * Revision 1.3 2005/11/17 16:29:25 fhesse 00052 * initial version 00053 * 00054 * Revision 1.2 2005/11/15 12:36:27 fhesse 00055 * muscles drawn as muscles, sphere drawn at tip of lower arm 00056 * 00057 * Revision 1.1 2005/11/11 15:37:06 fhesse 00058 * preinitial version 00059 * * 00060 * * 00061 ***************************************************************************/ 00062 00063 00064 #ifndef __MUSCLEDARM_H 00065 #define __MUSCLEDARM_H 00066 00067 #include "oderobot.h" 00068 #include <selforg/configurable.h> 00069 #include "primitive.h" 00070 #include "joint.h" 00071 00072 namespace lpzrobots{ 00073 00074 00075 00076 #define SIDE (0.2) /* side length of a box */ 00077 #define MASS (1.0) /* mass of a capped cylinder */ 00078 #define includeMusclesGraphics false 00079 00080 00081 /* Enumeration of different parts and joints */ 00082 // left, right up and down correspond to view from top, when base is on the bottom 00083 enum parts {base, upperArm, lowerArm, 00084 mainMuscle11, //left mainMuscle bottom part 00085 mainMuscle12, //left mainMuscle top part 00086 mainMuscle21, //right mainMuscle lower part 00087 mainMuscle22, //right mainMuscle upper part 00088 smallMuscle11, 00089 smallMuscle12, 00090 smallMuscle21, 00091 smallMuscle22, 00092 smallMuscle31, 00093 smallMuscle32, 00094 smallMuscle41, 00095 smallMuscle42, 00096 hand, 00097 NUMParts}; 00098 00099 enum joints {HJ_BuA, // hinge joint between base and upperArm 00100 HJ_uAlA, // hinge joint between upperArm and lowerArm 00101 00102 HJ_BmM11, // hinge joint between base and mainMuscle11 00103 HJ_lAmM12, // hinge joint between lowerArm and mainMuscle12 00104 HJ_BmM21, // hinge joint between base and mainMuscle21 00105 HJ_lAmM22, // hinge joint between lowerArm and mainMuscle22 00106 00107 HJ_BsM11, // hinge joint between base and smallMuscle11 00108 HJ_uAsM12, // hinge joint between upperArm and smallMuscle12 00109 HJ_BsM21, // hinge joint between base and smallMuscle21 00110 HJ_uAsM22, // hinge joint between upperArm and smallMuscle22 00111 HJ_lAsM31, // hinge joint between lowerArm and smallMuscle31 00112 HJ_uAsM32, // hinge joint between upperArm and smallMuscle32 00113 HJ_lAsM41, // hinge joint between lowerArm and smallMuscle41 00114 HJ_uAsM42, // hinge joint between upperArm and smallMuscle42 00115 00116 SJ_mM1, // sliderJoint between mainMuscle11 and mainMuscle12 00117 SJ_mM2, // sliderJoint between mainMuscle21 and mainMuscle22 00118 00119 SJ_sM1, // slider Joint between smallMuscle11 ans smallMuscle12 00120 SJ_sM2, // slider Joint between smallMuscle21 ans smallMuscle22 00121 SJ_sM3, // slider Joint between smallMuscle31 ans smallMuscle32 00122 SJ_sM4, // slider Joint between smallMuscle41 ans smallMuscle42 00123 NUMJoints}; 00124 00125 00126 00127 typedef struct { 00128 bool jointAngleSensors; // choose sensors, all combinations are possible 00129 bool jointAngleRateSensors; 00130 bool muscleLengthSensors; 00131 bool jointActuator; // if true, two motors at the joints are used 00132 // if false, six muscles are used 00133 00134 } MuscledArmConf; 00135 00136 class MuscledArm : public OdeRobot, public Configurable{ 00137 public: 00138 00139 double force_[6]; 00140 00141 MuscledArm(const OdeHandle& odeHandle, const OsgHandle& osgHandle, const MuscledArmConf& conf); 00142 00143 static MuscledArmConf getDefaultConf(){ 00144 MuscledArmConf conf; 00145 conf.jointAngleSensors=false; 00146 conf.jointAngleRateSensors=true; 00147 conf.muscleLengthSensors=false; 00148 conf.jointActuator=false; 00149 return conf; 00150 } 00151 00152 virtual ~MuscledArm(){}; 00153 00154 00155 /// update the subcomponents 00156 virtual void update(); 00157 00158 00159 /** sets the pose of the vehicle 00160 @param pose desired 4x4 pose matrix 00161 */ 00162 virtual void place(const osg::Matrix& pose); 00163 00164 00165 /** returns actual sensorvalues 00166 @param sensors sensors scaled to [-1,1] 00167 @param sensornumber length of the sensor array 00168 @return number of actually written sensors 00169 */ 00170 virtual int getSensors(sensor* sensors, int sensornumber); 00171 00172 /** sets actual motorcommands 00173 @param motors motors scaled to [-1,1] 00174 @param motornumber length of the motor array 00175 */ 00176 virtual void setMotors(const motor* motors, int motornumber); 00177 00178 /** returns number of sensors 00179 */ 00180 virtual int getSensorNumber(){ 00181 return sensorno; 00182 }; 00183 00184 /** returns number of motors 00185 */ 00186 virtual int getMotorNumber(){ 00187 return motorno; 00188 }; 00189 00190 /* /\** returns position of hand (=sphere at the end of lower arm) */ 00191 /* @return position robot position in struct Position */ 00192 /* *\/ */ 00193 /* virtual osg::Vec3 MuscledArm::getPosition(); */ 00194 00195 /** returns a vector with the positions of all segments of the robot 00196 @param poslist vector of positions (of all robot segments) 00197 @return length of the list 00198 */ 00199 virtual int getSegmentsPosition(vector<Position> &poslist); 00200 00201 virtual bool collisionCallback(void *data, dGeomID o1, dGeomID o2); 00202 /** this function is called in each timestep. It should perform robot-internal checks, 00203 like space-internal collision detection, sensor resets/update etc. 00204 @param globalData structure that contains global data from the simulation environment 00205 */ 00206 virtual void doInternalStuff(const GlobalData& globalData); 00207 00208 /// returns the name of the object (with version number) 00209 virtual paramkey getName() const {return name; } 00210 00211 /** The list of all parameters with there value as allocated lists. 00212 */ 00213 paramlist getParamList() const; 00214 00215 virtual paramval getParam(const paramkey& key) const; 00216 00217 virtual bool setParam(const paramkey& key, paramval val); 00218 00219 virtual Primitive* getMainObject() const; 00220 00221 protected: 00222 /** the main object of the robot, which is used for position and speed tracking */ 00223 virtual Primitive* getMainPrimitive() const { return object[lowerArm]; } 00224 00225 /** creates vehicle at desired pose 00226 @param pose 4x4 pose matrix 00227 */ 00228 virtual void create(const osg::Matrix& pose); 00229 00230 /** destroys vehicle and space 00231 */ 00232 virtual void destroy(); 00233 00234 static void mycallback(void *data, dGeomID o1, dGeomID o2); 00235 00236 double dBodyGetPositionAll ( dBodyID basis , int para ); 00237 double dGeomGetPositionAll ( dGeomID basis , int para ); 00238 00239 void BodyCreate(int n, dMass m, dReal x, dReal y, dReal z, 00240 dReal qx, dReal qy, dReal qz, dReal qangle); 00241 00242 MuscledArmConf conf; 00243 00244 static const int armanzahl= 3; 00245 00246 00247 Primitive* object[NUMParts]; 00248 Joint* joint[NUMJoints]; 00249 00250 Position old_dist[NUMParts]; // used for damping 00251 00252 string name; 00253 paramval factorMotors; 00254 paramval factorSensors; 00255 paramval damping; 00256 paramval print; 00257 00258 00259 00260 00261 int segmentsno; // number of motorsvehicle segments 00262 00263 00264 00265 double gelenkabstand; 00266 double SOCKEL_LAENGE; 00267 double SOCKEL_BREITE; 00268 double SOCKEL_HOEHE; 00269 double SOCKEL_MASSE; 00270 00271 int sensorno; //number of sensors 00272 int motorno; // number of motors 00273 00274 bool created; // true if robot was created 00275 00276 00277 00278 dSpaceID parentspace; 00279 00280 int printed; 00281 00282 double max_l; 00283 double max_r, min_l, min_r; 00284 00285 double base_width; 00286 double base_length; 00287 double upperArm_width; 00288 double upperArm_length; 00289 double lowerArm_width; 00290 double lowerArm_length; 00291 double joint_offset; 00292 double mainMuscle_width; 00293 double mainMuscle_length; 00294 double smallMuscle_width; 00295 double smallMuscle_length; 00296 00297 }; 00298 00299 } 00300 #endif