00001 /** 00002 * @file RobotDimensions.h 00003 * 00004 * Description of the Dimensions of the Robot 00005 * 00006 * @author Matthias Jüngel, Max Risler 00007 */ 00008 00009 #ifndef __RobotDimensions_H__ 00010 #define __RobotDimensions_H__ 00011 00012 #include "Tools/Math/Vector2.h" 00013 00014 class RobotDimensions 00015 { 00016 public: 00017 const double distancePanCenterToCameraX;//!<x-distance camera to center of head (specs) 00018 const double distancePanCenterToCameraZ;//!<z-distance camera to center of head (specs) 00019 const double distanceCameraToPSDSensor; //!<z-distanse camera to PSDsensor (estimated?) 00020 const double distanceNeckToPanCenter; //!<distance center of head to neck (specs) 00021 00022 const double shoulderWidth; //!<width between shoulder joints (specs) 00023 const double bodyWidth; //!<width between knee joints (specs) 00024 const double overallBodyWidth; //!<overall width of the body including legs (specs) 00025 00026 const double upperLegLengthX; //!<length upper leg joint to joint in x-direction (specs) 00027 const double upperLegLengthY; //!<length upper leg joint to joint in y-direction (calculated) 00028 const double upperLegLengthZ; //!<length upper leg joint to joint in z-direction (specs) 00029 const double upperLegLength; //!<length upper leg joint to joint (calculated) 00030 const double lowerForeLegLengthX; //!<length lower front leg joint to footbase in x-direction (specs) 00031 const double lowerForeLegLengthZ; //!<length lower front leg joint to footbase in z-direction (specs) 00032 const double lowerForeLegLength; //!<length lower front leg joint to footbase (calculated) 00033 const double lowerHindLegLengthX; //!<length lower rear leg joint to footbase in x-direction (specs) 00034 const double lowerHindLegLengthZ; //!<length lower rear leg joint to footbase in z-direction (specs) 00035 const double lowerHindLegLength; //!<length lower rear leg joint to footbase (calculated) 00036 const double lengthBetweenLegs; //!<length from front to rear legs (specs) 00037 const double neckToLegsLengthZ; //!<height from neck to front legs (specs) 00038 const double neckToLegsLengthX; //!<length from front legs to neck projected on x-axis (specs) 00039 const double lengthNeckToBodyCenter; //!<length from center of Robot to neck projected on x-axis (calculated) 00040 00041 const double zeroShoulderArc; //!<arc resulting from upperLegLengthX and -Z (calculated) 00042 const double specsKneeArc; //!<knee arc lower leg lengths are based on (specs) 00043 const double zeroFrontKneeArc; //!<arc resulting from lowerForeLegLengthX and -Z (calculated) 00044 const double zeroHindKneeArc; //!<arc resulting from lowerHindLegLengthX and -Z (calculated) 00045 const double zeroBodyTilt; //!<body tilt when all joints are 0 (calculated) 00046 00047 const double bodyLength; //!<length of robot body (estimated) 00048 const double lowerBodyWidth; //!<width of body core at bottom (estimated), 00049 const double shoulderRadius; //!< thickness of the body around the shoulder (estimated) 00050 const double kneeRadius; //!< thickness of the leg at the knee (estimated) 00051 const double footRadius; //!< thickness of the leg at the foot (estimated) 00052 00053 //!@name joint limits in rad (estimated) 00054 //!@{ 00055 const double jointLimitLeg1FN; 00056 const double jointLimitLeg1FP; 00057 const double jointLimitLeg1HN; 00058 const double jointLimitLeg1HP; 00059 const double jointLimitLeg2N; 00060 const double jointLimitLeg2P; 00061 const double jointLimitLeg3N; 00062 const double jointLimitLeg3P; 00063 00064 const double jointLimitNeckTiltN; 00065 const double jointLimitNeckTiltP; 00066 const double jointLimitHeadPanN; 00067 const double jointLimitHeadPanP; 00068 const double jointLimitHeadTiltN; 00069 const double jointLimitHeadTiltP; 00070 00071 const double jointLimitTailTiltN; 00072 const double jointLimitTailTiltP; 00073 const double jointLimitTailPanN; 00074 const double jointLimitTailPanP; 00075 //!@} 00076 00077 const double motionCycleTime; //! Length of one motion cycle in seconds. 00078 const double imagesPerSecond; //! image frame rate of the camera in Hz. 00079 00080 RobotDimensions( 00081 const double distancePanCenterToCameraX, 00082 const double distancePanCenterToCameraZ, 00083 const double distanceCameraToPSDSensor, 00084 const double distanceNeckToPanCenter, 00085 const double shoulderWidth, 00086 const double bodyWidth, 00087 const double overallBodyWidth, 00088 const double upperLegLengthX, 00089 const double upperLegLengthZ, 00090 const double lowerForeLegLengthX, 00091 const double lowerForeLegLengthZ, 00092 const double lowerHindLegLengthX, 00093 const double lowerHindLegLengthZ, 00094 const double lengthBetweenLegs, 00095 const double neckToLegsLengthX, 00096 const double neckToLegsLengthZ, 00097 const double specsKneeArc, 00098 const double bodyLength, 00099 const double lowerBodyWidth, 00100 const double shoulderRadius, 00101 const double kneeRadius, 00102 const double footRadius, 00103 const double jointLimitLeg1FN, 00104 const double jointLimitLeg1FP, 00105 const double jointLimitLeg1HN, 00106 const double jointLimitLeg1HP, 00107 const double jointLimitLeg2N, 00108 const double jointLimitLeg2P, 00109 const double jointLimitLeg3N, 00110 const double jointLimitLeg3P, 00111 const double jointLimitNeckTiltN, 00112 const double jointLimitNeckTiltP, 00113 const double jointLimitHeadPanN, 00114 const double jointLimitHeadPanP, 00115 const double jointLimitHeadTiltN, 00116 const double jointLimitHeadTiltP, 00117 const double jointLimitTailTiltN, 00118 const double jointLimitTailTiltP, 00119 const double jointLimitTailPanN, 00120 const double jointLimitTailPanP, 00121 const double motionCycleTime, 00122 const double imagesPerSecond 00123 ) 00124 : distancePanCenterToCameraX(distancePanCenterToCameraX), 00125 distancePanCenterToCameraZ(distancePanCenterToCameraZ), 00126 distanceCameraToPSDSensor(distanceCameraToPSDSensor), 00127 distanceNeckToPanCenter(distanceNeckToPanCenter), 00128 shoulderWidth(shoulderWidth), 00129 bodyWidth(bodyWidth), 00130 overallBodyWidth(overallBodyWidth), 00131 upperLegLengthX(upperLegLengthX), 00132 upperLegLengthY((bodyWidth - shoulderWidth) / 2), 00133 upperLegLengthZ(upperLegLengthZ), 00134 upperLegLength(Vector2<double>(upperLegLengthX, upperLegLengthZ).abs()), 00135 lowerForeLegLengthX(lowerForeLegLengthX), 00136 lowerForeLegLengthZ(lowerForeLegLengthZ), 00137 lowerForeLegLength(Vector2<double>(lowerForeLegLengthX, lowerForeLegLengthZ).abs()), 00138 lowerHindLegLengthX(lowerHindLegLengthX), 00139 lowerHindLegLengthZ(lowerHindLegLengthZ), 00140 lowerHindLegLength(Vector2<double>(lowerHindLegLengthX, lowerHindLegLengthZ).abs()), 00141 lengthBetweenLegs(lengthBetweenLegs), 00142 neckToLegsLengthX(neckToLegsLengthX), 00143 neckToLegsLengthZ(neckToLegsLengthZ), 00144 lengthNeckToBodyCenter(neckToLegsLengthX + lengthBetweenLegs / 2), 00145 zeroShoulderArc(atan2(upperLegLengthX, upperLegLengthZ)), 00146 specsKneeArc(specsKneeArc), 00147 zeroFrontKneeArc(zeroShoulderArc + specsKneeArc - atan2(lowerForeLegLengthX, lowerForeLegLengthZ)), 00148 zeroHindKneeArc(zeroShoulderArc + specsKneeArc - atan2(lowerHindLegLengthX, lowerHindLegLengthZ)), 00149 zeroBodyTilt(atan2(lowerHindLegLength * cos(zeroFrontKneeArc - zeroShoulderArc) - 00150 lowerForeLegLength * cos(zeroHindKneeArc - zeroShoulderArc), lengthBetweenLegs)), 00151 bodyLength(bodyLength), 00152 lowerBodyWidth(lowerBodyWidth), 00153 shoulderRadius(shoulderRadius), 00154 kneeRadius(kneeRadius), 00155 footRadius(footRadius), 00156 jointLimitLeg1FN(jointLimitLeg1FN), 00157 jointLimitLeg1FP(jointLimitLeg1FP), 00158 jointLimitLeg1HN(jointLimitLeg1HN), 00159 jointLimitLeg1HP(jointLimitLeg1HP), 00160 jointLimitLeg2N(jointLimitLeg2N), 00161 jointLimitLeg2P(jointLimitLeg2P), 00162 jointLimitLeg3N(jointLimitLeg3N), 00163 jointLimitLeg3P(jointLimitLeg3P), 00164 jointLimitNeckTiltN(jointLimitNeckTiltN), 00165 jointLimitNeckTiltP(jointLimitNeckTiltP), 00166 jointLimitHeadPanN(jointLimitHeadPanN), 00167 jointLimitHeadPanP(jointLimitHeadPanP), 00168 jointLimitHeadTiltN(jointLimitHeadTiltN), 00169 jointLimitHeadTiltP(jointLimitHeadTiltP), 00170 jointLimitTailTiltN(jointLimitTailTiltN), 00171 jointLimitTailTiltP(jointLimitTailTiltP), 00172 jointLimitTailPanN(jointLimitTailPanN), 00173 jointLimitTailPanP(jointLimitTailPanP), 00174 motionCycleTime(motionCycleTime), 00175 imagesPerSecond(imagesPerSecond) 00176 {} 00177 }; 00178 00179 class RobotDimensionsERS210 : public RobotDimensions 00180 { 00181 public: 00182 RobotDimensionsERS210() 00183 : RobotDimensions( 00184 66.6, // x-distance camera to center of head (specs) 00185 0.0, // z-distance camera to center of head (specs) 00186 10.0, // z-distanse camera to PSDsensor (?) 00187 48.0, // distance center of head to neck (specs) 00188 00189 118.4, // width between shoulder joints (specs) 00190 119.4, // width between knee joints (specs) 00191 152.0, // overall width of the body including legs (specs) 00192 12.8, // length upper leg joint to joint in x-direction (specs) 00193 64.0, // length upper leg joint to joint in z-direction (specs) 00194 22.4, // length lower front leg joint to footbase in x-direction (specs) 00195 64.9, // length lower front leg joint to footbase in z-direction (specs) 00196 16.6, // length lower rear leg joint to footbase in x-direction (specs) 00197 74.9, // length lower rear leg joint to footbase in z-direction (specs) 00198 119.0, // length from front to rear legs (specs) 00199 15.5, // length from front legs to neck projected on x-axis (specs) 00200 50.0, // height from neck to front legs (specs) 00201 0.611, // knee arc lower leg lengths are based on (35°, specs) 00202 200.0, // length of robot body (estimated) 00203 61.0, // width of body core at bottom (used to avoid ball inside the robot body, estimated) 00204 58.0, // thickness of the body around the shoulder (estimated) 00205 25.0, // thickness of the leg at the knee (estimated) 00206 10.0, // thickness of the leg at the foot (estimated) 00207 00208 -2.04, 2.04, // front leg joint 1 limits 00209 -2.04, 2.04, // rear leg joint 1 limits 00210 -0.2, 1.571, // leg joint 2 limits 00211 -0.46, 2.56, // leg joint 3 limits 00212 -1.571, 0.75, // head tilt joint limits 00213 -1.571, 1.571, // head pan joint limits 00214 -0.46, 0.46, // head roll joint limits 00215 -0.38, 0.38, // tail tilt joint limits 00216 -0.38, 0.38, // tail pan joint limits 00217 0.008, // motion cycle 00218 25) // 25 Hz 00219 {} 00220 }; 00221 00222 class RobotDimensionsERS7 : public RobotDimensions 00223 { 00224 public: 00225 RobotDimensionsERS7() 00226 : RobotDimensions( 00227 81.06, // x-distance camera to center of head (specs) 00228 14.6, // z-distance camera to center of head (specs) 00229 20.0, // z-distanse camera to PSDsensor (?) 00230 80.0, // distance center of head to neck (specs) 00231 00232 125.0, // width between shoulder joints (specs) 00233 134.4, // width between knee joints (specs) 00234 180.15, // overall width of the body including legs (specs) 00235 9.0, // length upper leg joint to joint in x-direction (specs) 00236 69.5, // length upper leg joint to joint in z-direction (specs) 00237 28.3, // length lower front leg joint to footbase in x-direction (specs) 00238 71.5, // length lower front leg joint to footbase in z-direction (specs) 00239 21.3, // length lower rear leg joint to footbase in x-direction (specs) 00240 76.5, // length lower rear leg joint to footbase in z-direction (specs) 00241 130.0, // length from front to rear legs (specs) 00242 2.5, // length from front legs to neck projected on x-axis (specs) 00243 19.5, // height from neck to front legs (specs) 00244 0.524, // knee arc lower leg lengths are based on (30°, specs) 00245 230.0, // length of robot body (estimated) 00246 80.0, // width of body core at bottom (used to avoid ball inside the robot body, estimated) 00247 52.0, // thickness of the body around the shoulder (estimated) 00248 13.0, // thickness of the leg at the knee (estimated) 00249 22.5, // thickness of the leg at the foot (seems to be suitable to express the curve of the lower leg) 00250 00251 -2.0944, 2.3562, // front leg joint 1 limits -120, 135 00252 -2.3562, 2.0944, // rear leg joint 1 limits -135, 120 00253 -0.2618, 1.6232, // leg joint 2 limits -15, 93 (specs) 00254 -0.5236, 2.2166, // leg joint 3 limits -30, 127 (specs) 00255 -1.3963, 0.0524, // head tilt joint limits -80, 3 (specs) 00256 -1.6232, 1.6232, // head pan joint limits -93, 93 (specs) 00257 -0.3491, 0.8727, // head tilt2 joint limits -20, 50 (specs) 00258 +0.0000, 1.1345, // tail tilt joint limits 0, 65 (specs) 00259 -1.0472, 1.0472, // tail pan joint limits -60, 60 (specs) 00260 0.008, // motion cycle 00261 30) // 30 Hz 00262 {} 00263 }; 00264 #endif 00265 00266 /* 00267 * Change log : 00268 * 00269 * $Log: RobotDimensions.h,v $ 00270 * Revision 1.3 2004/06/05 07:58:22 roefer 00271 * Compensation for motion distortions of images 00272 * 00273 * Revision 1.2 2004/05/27 17:13:38 jhoffman 00274 * - renaming: tilt1 -> neckTilt, pan -> headPan, tilt2 -> headTilt 00275 * - clipping included for setJoints 00276 * - removed some microrad/rad-bugs 00277 * - bodyPosture constructor and "=" operator fixed 00278 * 00279 * Revision 1.1.1.1 2004/05/22 17:36:01 cvsadm 00280 * created new repository GT2004_WM 00281 * 00282 * Revision 1.21 2004/03/11 17:02:27 risler 00283 * different limits for front and hind leg joint 1 for ERS-7 00284 * 00285 * Revision 1.20 2004/03/10 08:02:28 roefer 00286 * Limits of ERS-7 head joints corrected 00287 * 00288 * Revision 1.19 2004/02/26 23:03:31 roefer 00289 * CameraMatrix improved 00290 * 00291 * Revision 1.18 2004/02/24 19:01:06 roefer 00292 * Additional calibration parameters added 00293 * 00294 * Revision 1.17 2004/02/24 00:01:21 roefer 00295 * CameraMatrix improved 00296 * 00297 * Revision 1.16 2004/02/06 20:25:36 roefer 00298 * ERS-7 knee radius changed 00299 * 00300 * Revision 1.15 2004/01/28 21:55:50 roefer 00301 * RobotDimensions revised 00302 * 00303 * Revision 1.14 2004/01/23 00:13:24 roefer 00304 * ERS-7 simulation, first draft 00305 * 00306 * Revision 1.13 2004/01/14 19:18:01 mellmann 00307 * Added distanceCameraToPSDSensor. 00308 * 00309 * Revision 1.12 2004/01/08 18:19:28 mkunz 00310 * distancePanCenterToCamera -> distancePanCenterToCameraX 00311 * new: distancePanCenterToCameraZ 00312 * 00313 * Revision 1.11 2004/01/06 14:14:52 mellmann 00314 * added ERS7 dimensions 00315 * 00316 * Revision 1.10 2004/01/05 17:54:05 juengel 00317 * Added joint limits for head and tail for ERS7. 00318 * 00319 * Revision 1.9 2004/01/05 10:02:15 juengel 00320 * Prepared RobotDimensionsERS7. 00321 * 00322 * Revision 1.8 2004/01/03 16:36:13 roefer 00323 * motionCycleTime 8 ms -> 0.008 s 00324 * 00325 * Revision 1.7 2004/01/01 10:58:51 roefer 00326 * RobotDimensions are in a class now 00327 * 00328 * Revision 1.6 2003/12/31 23:51:40 roefer 00329 * Removed unused constants 00330 * 00331 * Revision 1.5 2003/12/30 20:12:04 roefer 00332 * Image size is now 208 x 160. Smaller images are placed in the upper left corner 00333 * 00334 * Revision 1.4 2003/12/15 11:49:09 juengel 00335 * Introduced CameraInfo 00336 * 00337 * Revision 1.3 2003/12/02 18:10:11 dueffert 00338 * missing correction values added 00339 * 00340 * Revision 1.2 2003/10/23 15:41:40 roefer 00341 * Oracled obstacle model added 00342 * 00343 * Revision 1.1 2003/10/07 10:13:21 cvsadm 00344 * Created GT2004 (M.J.) 00345 * 00346 * Revision 1.1 2003/09/26 11:40:40 juengel 00347 * - sorted tools 00348 * - clean-up in DataTypes 00349 * 00350 * Revision 1.3 2003/09/12 12:11:57 dueffert 00351 * knee position added 00352 * 00353 * Revision 1.2 2003/07/03 10:26:45 roefer 00354 * lower body width 00355 * 00356 * Revision 1.1.1.1 2003/07/02 09:40:28 cvsadm 00357 * created new repository for the competitions in Padova from the 00358 * tamara CVS (Tuesday 2:00 pm) 00359 * 00360 * removed unused solutions 00361 * 00362 * Revision 1.8 2003/06/17 13:47:02 dueffert 00363 * constants added 00364 * 00365 * Revision 1.7 2003/04/15 15:52:07 risler 00366 * DDD GO 2003 code integrated 00367 * 00368 * Revision 1.7 2003/03/26 17:45:27 max 00369 * bodyLength added 00370 * 00371 * Revision 1.6 2003/03/15 13:30:26 juengel 00372 * Added joint limits for tail. 00373 * 00374 * Revision 1.5 2003/02/21 16:34:16 dueffert 00375 * common pi in own code, warnings removed, platform compatibility restored 00376 * 00377 * Revision 1.4 2002/11/19 15:43:03 dueffert 00378 * doxygen comments corrected 00379 * 00380 * Revision 1.3 2002/10/10 13:31:05 jhoffman 00381 * added camera parameters 00382 * 00383 * Revision 1.2 2002/09/22 18:40:53 risler 00384 * added new math functions, removed GTMath library 00385 * 00386 * Revision 1.1 2002/09/10 15:53:58 cvsadm 00387 * Created new project GT2003 (M.L.) 00388 * - Cleaned up the /Src/DataTypes directory 00389 * - Removed challenge related source code 00390 * - Removed processing of incoming audio data 00391 * - Renamed AcousticMessage to SoundRequest 00392 * 00393 * Revision 1.2 2002/06/04 11:01:41 juengel 00394 * jointLimitNeckTiltP modified. 00395 * 00396 * Revision 1.1.1.1 2002/05/10 12:40:32 cvsadm 00397 * Moved GT2002 Project from ute to tamara. 00398 * 00399 * Revision 1.10 2002/04/05 16:46:20 kosen 00400 * BremenGOWalkingEngine added 00401 * 00402 * Revision 1.9 2002/04/03 13:25:41 risler 00403 * changed doubles to Value/Angle, tan to tan 00404 * 00405 * Revision 1.8 2002/04/02 14:01:39 dueffert 00406 * minor odometry enhancements 00407 * 00408 * Revision 1.7 2002/04/02 13:10:22 dueffert 00409 * big change: odometryData and cameraMatrix in image now, old logfiles may be obsolete 00410 * 00411 * Revision 1.6 2002/02/06 10:30:11 AndySHB 00412 * MonteCarloLocalization First Draft 00413 * 00414 * Revision 1.5 2002/01/30 01:08:56 dueffert 00415 * fixed endless-compile-bug caused by up/downcase difference MathLib vs. Mathlib, makefile should be caseUNsensitive (in such cases) now 00416 * 00417 * Revision 1.4 2002/01/19 21:36:24 risler 00418 * added HeadMotionTester, HeadControlSelector 00419 * 00420 * Revision 1.3 2001/12/13 19:13:58 risler 00421 * added odometry updates in GT2001MotionNetSpecialActions 00422 * 00423 * Revision 1.2 2001/12/10 17:47:10 risler 00424 * change log added 00425 * 00426 */