00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #include "Platform/GTAssert.h"
00014 #include "GT2004HeadControl.h"
00015 #include "Tools/Math/Geometry.h"
00016 #include "Tools/Actorics/Kinematics.h"
00017 #include "Tools/Math/Common.h"
00018 #include "Tools/FieldDimensions.h"
00019 #include "Platform/SystemCall.h"
00020
00021
00022 #ifdef _WIN32
00023 #pragma warning(disable:4355) // VC++: "this" in initializer list is ok
00024 #endif
00025
00026 GT2004HeadControl::GT2004HeadControl(HeadControlInterfaces& interfaces)
00027 : Xabsl2HeadControl(interfaces, SolutionRequest::hc_gt2004),
00028 headPathPlanner(sensorDataBuffer),
00029 symbols(interfaces,*this,basicBehaviors.basicBehaviorDirectedScanForLandmarks),
00030 basicBehaviors(errorHandler,*this,*this,headPathPlanner,lastScanWasLeft,cameraInfo),
00031 lastScanWasLeft(true),
00032 lastHeadControlMode(HeadControlMode::none),
00033 lastOdometryData(), lastRobotPose()
00034 {
00035 Xabsl2FileInputSource file("Xabsl2/HeadCtrl/gt04-ic.dat");
00036 init(file);
00037
00038 headPathPlanner.lastNeckTilt = ((double )sensorDataBuffer.lastFrame().data[SensorData::neckTilt])/1000000.0;
00039 headPathPlanner.lastHeadPan = ((double )sensorDataBuffer.lastFrame().data[SensorData::headPan])/1000000.0;
00040 headPathPlanner.lastHeadTilt = ((double )sensorDataBuffer.lastFrame().data[SensorData::headTilt])/1000000.0;
00041
00042 const RobotDimensions& robotDimensions = getRobotConfiguration().getRobotDimensions();
00043 cameraInfo = CameraInfo::CameraInfo(getRobotConfiguration().getRobotDesign());
00044
00045 setupMainAngles();
00046
00047 jointRangeNeckTilt = Range<double>(robotDimensions.jointLimitNeckTiltN,robotDimensions.jointLimitNeckTiltP);
00048 jointRangeHeadPan = Range<double>(robotDimensions.jointLimitHeadPanN, robotDimensions.jointLimitHeadPanP);
00049 jointRangeHeadTilt = Range<double>(robotDimensions.jointLimitHeadTiltN,robotDimensions.jointLimitHeadTiltP);
00050
00051
00052 speedNeckTilt = 0.002000;
00053 speedHeadPan = 0.005350;
00054 speedHeadTilt = 0.002550;
00055
00056
00057 headPathPlanner.headPathSpeedNeckTilt = speedNeckTilt;
00058 headPathPlanner.headPathSpeedHeadPan = speedHeadPan;
00059 headPathPlanner.headPathSpeedHeadTilt = speedHeadTilt;
00060
00061 calibrationReset();
00062
00063 useCommunicatedBall = true;
00064
00065
00066 }
00067
00068 int GT2004HeadControl::getLastSeenBeaconIndex()
00069 {
00070 return landmarksState.lastSeenBeaconIndex();
00071 }
00072 long GT2004HeadControl::getTimeOfLastSeenBeacon(int index)
00073 {
00074 return landmarksState.timeOfLastSeenBeacon(index);
00075 }
00076
00077 long GT2004HeadControl::getTimeBetweenSeen2LastBeacons(int index)
00078 {
00079 return landmarksState.timeBetweenSeen2LastBeacons(index);
00080 }
00081
00082 bool GT2004HeadControl::headPanIsLeft()
00083 {
00084 return ((((double )sensorDataBuffer.lastFrame().data[SensorData::headPan]))>0);
00085 }
00086
00087 void GT2004HeadControl::getSensorHeadAngles(Vector3<double>& pos)
00088 {
00089 pos.x = ((double )sensorDataBuffer.lastFrame().data[SensorData::neckTilt])/1000000.0;
00090 pos.y = ((double )sensorDataBuffer.lastFrame().data[SensorData::headPan])/1000000.0;
00091 pos.z = ((double )sensorDataBuffer.lastFrame().data[SensorData::headTilt])/1000000.0;
00092 }
00093
00094 void GT2004HeadControl::searchForBallRight()
00095 {
00096 Vector3<double> points[]={ headDown,
00097 headMiddleRight,
00098 headRight,
00099 headRight};
00100
00101 long durations[] = {100,100,200,160};
00102 headPathPlanner.init(points,durations,sizeof(points)/sizeof(Vector3<double>));
00103
00104 lastScanWasLeft = false;
00105 }
00106
00107 void GT2004HeadControl::searchForBallLeft()
00108 {
00109 Vector3<double> points[]={ headDown,
00110 headMiddleLeft,
00111 headLeft,
00112 headLeft};
00113
00114 long durations[] = {100,100,200,160};
00115 headPathPlanner.init(points,durations,sizeof(points)/sizeof(Vector3<double>));
00116
00117 lastScanWasLeft = true;
00118 }
00119
00120 double GT2004HeadControl::headPositionDistanceToActualPosition(Vector3<double> comp,bool leftSide)
00121 {
00122 double pos;
00123 pos = ((double)sensorDataBuffer.lastFrame().data[SensorData::headPan])/1000000.0;
00124
00125 return -fabs(pos-comp.y);;
00126
00127 }
00128 void GT2004HeadControl::registerSymbolsAndBasicBehaviors()
00129 {
00130 symbols.registerSymbols(*pEngine);
00131 basicBehaviors.registerBasicBehaviors(*pEngine);
00132 }
00133
00134 void GT2004HeadControl::execute()
00135 {
00136 symbols.update();
00137
00138 if(headIsBlockedBySpecialActionOrWalk)
00139 {
00140 headPathPlanner.lastNeckTilt = ((double )sensorDataBuffer.lastFrame().data[SensorData::neckTilt])/1000000.0;
00141 headPathPlanner.lastHeadPan = ((double )sensorDataBuffer.lastFrame().data[SensorData::headPan])/1000000.0;
00142 headPathPlanner.lastHeadTilt = ((double )sensorDataBuffer.lastFrame().data[SensorData::headTilt])/1000000.0;
00143 }
00144
00145 if(sensorDataBuffer.lastFrame().data[SensorData::chin] == 1)
00146 {
00147 if(
00148 robotState.getButtonPressed(BodyPercept::backBack) &&
00149 robotState.getButtonDuration(BodyPercept::backBack) > 1000 &&
00150 profiler.profilerCollectMode == GTXabsl2Profiler::collectProfiles
00151 )
00152 {
00153 profiler.profilerCollectMode = GTXabsl2Profiler::dontCollectProfiles;
00154 profiler.profilerWriteMode = GTXabsl2Profiler::writeCompleteProfiles;
00155 }
00156
00157 if(
00158 robotState.getButtonPressed(BodyPercept::backFront) &&
00159 robotState.getButtonDuration(BodyPercept::backFront) > 1000
00160 )
00161 {
00162 profiler.profilerCollectMode = GTXabsl2Profiler::collectProfiles;
00163 }
00164 }
00165
00166 executeEngine();
00167
00168 lastHeadControlMode = headControlMode.headControlMode;
00169 }
00170
00171
00172
00173 bool GT2004HeadControl::handleMessage(InMessage& message)
00174 {
00175 return Xabsl2HeadControl::handleMessage(message);
00176 }
00177
00178
00179 void GT2004HeadControl::beginBallSearchAt(Vector2<double> ballPosition2d)
00180 {
00181 Vector3<double> ballPosition3d (ballPosition2d.x,ballPosition2d.y,ballRadius);
00182
00183 Vector3<double> leftRightSweepTop,
00184 leftRightSweepBottom,
00185 halfLeftRightSweep,
00186 halfLeftRightSweepBottom;
00187
00188 Vector2<double> toBall = ballPosition2d - robotPose.translation;
00189 double angleToBall = normalize(atan2(toBall.y,toBall.x))-robotPose.rotation;
00190
00191
00192
00193
00194 enum { ballNearBy = 500 };
00195 Vector2<int> cameraImageOffset(0,25);
00196
00197 double neckTilt,headPan,headTilt;
00198 simpleLookAtPointOnField(ballPosition3d,cameraImageOffset,neckTilt,headPan,headTilt);
00199 Vector3<double> ballAngles (neckTilt,headPan,headTilt);
00200
00201 if (angleToBall>0)
00202 {
00203 leftRightSweepTop = headLeft;
00204 leftRightSweepBottom = headLeftDown;
00205 halfLeftRightSweep = headMiddleLeft;
00206 halfLeftRightSweepBottom = headMiddleLeftDown;
00207
00208 }
00209 else
00210 {
00211 leftRightSweepTop = headRight;
00212 leftRightSweepBottom = headRightDown;
00213 halfLeftRightSweep = headMiddleRight;
00214 halfLeftRightSweepBottom = headMiddleRightDown;
00215 }
00216
00217 Vector3<double> points[]={ballAngles,
00218 ballAngles,
00219 leftRightSweepBottom,
00220 leftRightSweepTop,
00221 halfLeftRightSweep,
00222 headUp,
00223 headDown};
00224
00225 long durations[] = {0,100,160,120,160,100,80};
00226 headPathPlanner.init(points,durations,sizeof(points)/sizeof(Vector3<double>));
00227 lastScanWasLeft = (angleToBall>0);
00228
00229
00230 }
00231 void GT2004HeadControl::setJointsDirect(double neckTilt, double headPan, double headTilt, double mouth)
00232 {
00233 headPathPlanner.lastNeckTilt = jointRangeNeckTilt.limit(neckTilt);
00234 headPathPlanner.lastHeadPan = jointRangeHeadPan.limit(headPan);
00235 headPathPlanner.lastHeadTilt = jointRangeHeadTilt.limit(headTilt);
00236
00237 headMotionRequest.tilt = toMicroRad(neckTilt);
00238 headMotionRequest.pan = toMicroRad(headPan);
00239 headMotionRequest.roll = toMicroRad(headTilt);
00240 headMotionRequest.mouth = toMicroRad(mouth);
00241 }
00242
00243 void GT2004HeadControl::setJoints(double neckTilt, double headPan, double headTilt, double speed, double mouth)
00244 {
00245 const double closeToDesiredAngles = 0.01;
00246
00247
00248
00249
00250 setJointsIsCloseToDestination = headPathPlanner.headPositionReached(Vector3<double> (neckTilt,headPan,headTilt));
00251
00252 setJointsMaxPanReached = false;
00253
00254 Vector2<double>
00255 direction(headTilt - headPathPlanner.lastHeadTilt,
00256 headPan - (headPathPlanner.lastHeadPan));
00257
00258 if (speed > 0)
00259 {
00260 Vector2<double> directionWithSpeed = direction;
00261 directionWithSpeed.normalize();
00262 directionWithSpeed *= speed/125;
00263 if (directionWithSpeed.abs() < direction.abs())
00264 direction = directionWithSpeed;
00265 }
00266
00267 if (direction.abs() < closeToDesiredAngles)
00268 setJointsIsCloseToDestination++;
00269 else
00270 setJointsIsCloseToDestination = 0;
00271
00272 headPathPlanner.lastNeckTilt = neckTilt;
00273 headPathPlanner.lastHeadPan += direction.y;
00274 headPathPlanner.lastHeadTilt += direction.x;
00275
00276 headPathPlanner.lastNeckTilt = jointRangeNeckTilt.limit(headPathPlanner.lastNeckTilt);
00277 headPathPlanner.lastHeadPan = jointRangeHeadPan.limit(headPathPlanner.lastHeadPan);
00278 headPathPlanner.lastHeadTilt = jointRangeHeadTilt.limit(headPathPlanner.lastHeadTilt);
00279
00280 if (fabs(headPathPlanner.lastHeadPan) == jointRangeHeadPan.max)
00281 setJointsMaxPanReached = true;
00282
00283 headMotionRequest.tilt = (long)(headPathPlanner.lastNeckTilt*1000000.0);
00284 headMotionRequest.pan = (long)(headPathPlanner.lastHeadPan *1000000.0);
00285 headMotionRequest.roll = (long)(headPathPlanner.lastHeadTilt*1000000.0);
00286 #ifndef _WIN32
00287
00288 #endif
00289 headMotionRequest.mouth = (long)(mouth*1000000);
00290
00291 if(lastRobotPose != robotPose)
00292 {
00293 lastOdometryData = currentOdometryData;
00294 lastRobotPose = robotPose;
00295 }
00296 }
00297
00298
00299
00300
00301
00302 void GT2004HeadControl::aimAtLandmark(int landmark, double& neckTilt, double& headPan, double& headTilt)
00303 {
00304 if(targetPointOnLandmark[landmark].height > 0)
00305 {
00306 simpleLookAtPointOnField(
00307 targetPointOnLandmark[landmark].position,
00308 Vector2<int>(0, -cameraInfo.resolutionHeight/3),
00309 neckTilt, headPan, headTilt);
00310 }
00311 else
00312 {
00313 simpleLookAtPointOnField(
00314 targetPointOnLandmark[landmark].position,
00315 Vector2<int>(0, 0),
00316 neckTilt, headPan, headTilt);
00317 }
00318 }
00319
00320
00321
00322 void GT2004HeadControl::getLookAtBallAngles(const Vector2<double> ballOnField, double& neckTilt, double& headPan, double& headTilt)
00323 {
00324
00325 Vector2<double> ballPos = Geometry::fieldCoord2Relative(robotPose, ballOnField);
00326 if (ballPos.abs() < 100)
00327 ballPos.x = 100;
00328
00329 double minBClose = 300, maxBClose = 2000;
00330 Range<double> ballCloseRange(minBClose, maxBClose);
00331 double ballIsClose = ballPos.abs();
00332 ballIsClose = ballCloseRange.limit(ballIsClose);
00333 ballIsClose = (ballIsClose - minBClose)/(maxBClose-minBClose);
00334
00335 simpleLookAtPointRelativeToRobot(
00336 Vector3<double>(ballPos.x, ballPos.y, 1.8*ballRadius),
00337 Vector2<int>(0, int( (.167-ballIsClose)*cameraInfo.resolutionHeight/3)),
00338 neckTilt, headPan, headTilt);
00339 }
00340
00341 void GT2004HeadControl::simpleLookAtPointRelativeToRobot(const Vector3<double> pos, Vector2<int> offsetInImage,
00342 double& neckTilt, double& headPan, double& headTilt)
00343 {
00344 Vector3<double> target(pos);
00345
00346
00347 target.z -= bodyPosture.neckHeightCalculatedFromLegSensors;
00348 RotationMatrix bodyRotation;
00349 bodyRotation.rotateY(-bodyPosture.bodyTiltCalculatedFromLegSensors).
00350 rotateX(bodyPosture.bodyRollCalculatedFromLegSensors);
00351 target = bodyRotation*target;
00352
00353
00354 neckTilt = -0.0;
00355 if (!simpleLookAtPointFixNeckTilt(target, neckTilt, headPan, headTilt))
00356 {
00357 if (headTilt < jointLimitHeadTiltN)
00358 {
00359 neckTilt = headTilt - jointLimitHeadTiltN;
00360 headTilt = jointLimitHeadTiltN;
00361 }
00362 else if (headTilt > jointLimitHeadTiltP)
00363 {
00364
00365 headTilt = jointLimitHeadTiltP;
00366 }
00367
00368
00369 }
00370
00371
00372
00373
00374 const Range<int> cameraResY(-cameraInfo.resolutionHeight / 2, cameraInfo.resolutionHeight / 2);
00375 const Range<int> cameraResX(-cameraInfo.resolutionWidth / 2, cameraInfo.resolutionWidth / 2);
00376 offsetInImage.x = cameraResX.limit(offsetInImage.x);
00377 offsetInImage.y = cameraResY.limit(offsetInImage.y);
00378
00379
00380 headPan += ((double)offsetInImage.x/cameraInfo.resolutionWidth)*cameraInfo.openingAngleWidth;
00381 headTilt += ((double)offsetInImage.y/cameraInfo.resolutionHeight)*cameraInfo.openingAngleHeight;
00382
00383
00384 const Range<double> jointRangeNeckTilt(jointLimitNeckTiltN,jointLimitNeckTiltP);
00385 const Range<double> jointRangeHeadPan(jointLimitHeadPanN, jointLimitHeadPanP);
00386 const Range<double> jointRangeHeadTilt(jointLimitHeadTiltN, jointLimitHeadTiltP);
00387 neckTilt = jointRangeNeckTilt.limit(neckTilt);
00388 headPan = jointRangeHeadPan.limit(headPan);
00389 headTilt = jointRangeHeadTilt.limit(headTilt);
00390 }
00391
00392
00393 void GT2004HeadControl::simpleLookAtPointOnField(const Vector3<double> pos, Vector2<int> offsetInImage,
00394 double& neckTilt, double& headPan, double& headTilt)
00395 {
00396
00397 Vector3<double> target(pos);
00398 Pose2D robotPose = this->robotPose.getPose();
00399 target.x -= robotPose.translation.x;
00400 target.y -= robotPose.translation.y;
00401
00402 RotationMatrix bodyRotation;
00403 bodyRotation.rotateZ(-robotPose.getAngle());
00404 target = bodyRotation*target;
00405
00406 simpleLookAtPointRelativeToRobot(target, offsetInImage, neckTilt, headPan, headTilt);
00407 }
00408
00409
00410 bool GT2004HeadControl::simpleLookAtPointFixNeckTilt(const Vector3<double> &aim, const double& neckTilt, double& headPan, double& headTilt)
00411 {
00412 Vector3<double> target(aim);
00413
00414 RotationMatrix rotationByNeckTilt;
00415 rotationByNeckTilt.rotateY(neckTilt);
00416 target.z -= distanceNeckToPanCenter;
00417 target = rotationByNeckTilt*target;
00418
00419 headPan = atan2(target.y, target.x);
00420
00421 RotationMatrix rotationByHeadPan;
00422 rotationByHeadPan.rotateZ(-headPan);
00423 target = rotationByHeadPan*target;
00424
00425 headTilt = atan2(target.z, target.x);
00426
00427
00428
00429
00430
00431 if ((headTilt < jointLimitHeadTiltN) || (headTilt > jointLimitHeadTiltP) ||
00432 (headPan < jointLimitHeadPanN) || (headPan > jointLimitHeadPanP))
00433 return false;
00434
00435 return true;
00436 }
00437
00438
00439 int GT2004HeadControl::calculateClosestLandmark(double direction, double nextLeftOrRight)
00440 {
00441 int i, closest = -1;
00442 double smallestAngle = 3;
00443
00444 LINE(headControlField,
00445 robotPose.translation.x, robotPose.translation.y,
00446 robotPose.translation.x + 4000*cos(direction+robotPose.rotation), robotPose.translation.y + 4000*sin(direction+robotPose.rotation),
00447 20, 0, Drawings::blue);
00448
00449
00450 for (i = 0; i < numOfLandmarks; i++)
00451 {
00452 CIRCLE(headControlField,
00453 targetPointOnLandmark[i].position.x, targetPointOnLandmark[i].position.y, 50,
00454 2, 0, Drawings::blue);
00455
00456 Vector2<double> landMarkInRobotCoordinates(targetPointOnLandmark[i].position.x, targetPointOnLandmark[i].position.y);
00457 landMarkInRobotCoordinates -= robotPose.translation;
00458 double distToLandmark = landMarkInRobotCoordinates.abs();
00459
00460 if (((targetPointOnLandmark[i].height > 0) && (distToLandmark > 250)) ||
00461 ((targetPointOnLandmark[i].height == 0) && (distToLandmark > 250) && (distToLandmark < 1500)))
00462 {
00463 double angleToLandmark;
00464
00465 if (nextLeftOrRight == 0)
00466 {
00467 angleToLandmark = fabs(normalize(
00468 landMarkInRobotCoordinates.angle() - robotPose.rotation - direction));
00469 }
00470 else
00471 {
00472 angleToLandmark = sgn(nextLeftOrRight)*(normalize(
00473 landMarkInRobotCoordinates.angle() - robotPose.rotation - direction));
00474 }
00475
00476 if((0.0 <= angleToLandmark ) && (angleToLandmark < smallestAngle))
00477 {
00478 CIRCLE(headControlField,
00479 targetPointOnLandmark[i].position.x, targetPointOnLandmark[i].position.y, 50,
00480 2, 0, Drawings::blue);
00481
00482 smallestAngle = angleToLandmark;
00483 closest = i;
00484 }
00485 }
00486 }
00487 return closest;
00488 }
00489
00490 void GT2004HeadControl::setupMainAngles()
00491 {
00492 headLeft.x = 0.052400;
00493 headLeft.y = 1.573200;
00494 headLeft.z = -0.120000;
00495
00496 headLeftDown.x = 0.052400;
00497 headLeftDown.y = 1.573200;
00498 headLeftDown.z = -0.350000;
00499
00500 headRight.x = 0.052400;
00501 headRight.y = -1.573200;
00502 headRight.z = -0.0120000;
00503
00504 headRightDown.x = 0.052400;
00505 headRightDown.y = -1.573200;
00506 headRightDown.z = -0.350000;
00507
00508 headMiddleLeft.x = 0.052400;
00509 headMiddleLeft.y = 0.560000;
00510 headMiddleLeft.z = 0.062000;
00511
00512 headMiddleLeftDown.x = -0.1;
00513 headMiddleLeftDown.y = 0.560000;
00514 headMiddleLeftDown.z = -0.2;
00515
00516 headMiddleRight.x = 0.052400;
00517 headMiddleRight.y = -0.560000;
00518 headMiddleRight.z = 0.062000;
00519
00520 headMiddleRightDown.x = -0.1;
00521 headMiddleRightDown.y = -0.560000;
00522 headMiddleRightDown.z = -0.2;
00523
00524 headUp.x = 0.052400;
00525 headUp.y = 0;
00526 headUp.z = 0.034500;
00527
00528 headDown.x = -0.55000;
00529 headDown.y = 0;
00530 headDown.z = -2.8;
00531 }
00532
00533
00534 void GT2004HeadControl::calibrateHeadSpeed()
00535 {
00536
00537
00538
00539
00540
00541 Vector3<double> calibrationTilt1Down (-1.385604,0.0,0.040000);
00542 Vector3<double> calibrationTilt1Up (0.052359,0.0,0.040000);
00543
00544 Vector3<double> calibrationTilt2Down (0.0,0.0,-0.326175);
00545 Vector3<double> calibrationTilt2Up (0.0,0.0,0.750630);
00546
00547 Vector3<double> calibrationLeft (0.052400, 1.608598,-0.120000);
00548 Vector3<double> calibrationRight (0.052400,-1.608598,-0.120000);
00549
00550 enum {calibrationRounds = 3};
00551
00552 if (headPathPlanner.isLastPathFinished() || calibrationState == calibrationStateStart)
00553 {
00554 switch(calibrationState)
00555 {
00556 case calibrationStateStart:
00557 {
00558 Vector3<double> points[]={headUp,headUp};
00559 long durations[] = {0,1000};
00560
00561 headPathPlanner.init(points,durations,sizeof(points)/sizeof(Vector3<double>));
00562 calibrationState = calibrationStateLeft;
00563 calibrationRoundCount = 0;
00564 calibrationSuccessfulRounds = 0;
00565 speedNeckTilt = 0;
00566 speedHeadPan = 0;
00567 speedHeadTilt = 0;
00568 break;
00569 }
00570 case calibrationStateLeft:
00571 {
00572 Vector3<double> points[]={calibrationLeft,calibrationLeft};
00573 long durations[] = {2000,200};
00574 headPathPlanner.init(points,durations,sizeof(points)/sizeof(Vector3<double>),false);
00575 calibrationState = calibrationStateLeftWait;
00576 calibrationTime = SystemCall::getCurrentSystemTime();
00577 break;
00578 }
00579 case calibrationStateLeftWait:
00580 if (headPositionReached(calibrationLeft) || isTimedOut())
00581 calibrationState = calibrationStateRight;
00582 break;
00583 case calibrationStateRight:
00584 {
00585 Vector3<double> points[]={calibrationRight};
00586 long durations[] = {0};
00587 headPathPlanner.init(points,durations,sizeof(points)/sizeof(Vector3<double>),false);
00588 calibrationState = calibrationStateRightWait;
00589 calibrationTime = SystemCall::getCurrentSystemTime();
00590 break;
00591 }
00592 case calibrationStateRightWait:
00593 if (headPositionReached(calibrationRight) || isTimedOut())
00594 {
00595 if (!isTimedOut())
00596 {
00597 speedHeadPan += fabs(calibrationLeft.y-calibrationRight.y) / (SystemCall::getTimeSince(calibrationTime)+0.0001);
00598 calibrationSuccessfulRounds++;
00599 }
00600 else
00601 calibrationTimeOutsPan++;
00602 if (calibrationRoundCount < calibrationRounds-1)
00603 {
00604 calibrationState = calibrationStateLeft;
00605 calibrationRoundCount++;
00606 }
00607 else
00608 {
00609
00610 speedHeadPan /= calibrationSuccessfulRounds;
00611 calibrationSuccessfulRounds = 0;
00612 calibrationRoundCount = 0;
00613 calibrationState = calibrationStateDownTilt1;
00614 }
00615 }
00616 break;
00617 case calibrationStateDownTilt1:
00618 {
00619 Vector3<double> points[]={calibrationTilt1Down,calibrationTilt1Down};
00620 long durations[] = {1500,200};
00621 headPathPlanner.init(points,durations,sizeof(points)/sizeof(Vector3<double>),false);
00622 calibrationState = calibrationStateDownTilt1Wait;
00623 calibrationTime = SystemCall::getCurrentSystemTime();
00624 break;
00625 }
00626 case calibrationStateDownTilt1Wait:
00627 if (headPositionReached(calibrationTilt1Down) || isTimedOut())
00628 calibrationState = calibrationStateUpTilt1;
00629 break;
00630 case calibrationStateUpTilt1:
00631 {
00632 Vector3<double> points[]={calibrationTilt1Up};
00633 long durations[] = {0};
00634 headPathPlanner.init(points,durations,sizeof(points)/sizeof(Vector3<double>),false);
00635 calibrationState = calibrationStateUpTilt1Wait;
00636 calibrationTime = SystemCall::getCurrentSystemTime();
00637 break;
00638 }
00639 case calibrationStateUpTilt1Wait:
00640 if (headPositionReached(calibrationTilt1Up) || isTimedOut())
00641 {
00642 if (!isTimedOut())
00643 {
00644 speedNeckTilt += fabs(calibrationTilt1Down.x-calibrationTilt1Up.x) / (SystemCall::getTimeSince(calibrationTime)+0.0001);
00645 calibrationSuccessfulRounds++;
00646 }
00647 else
00648 calibrationTimeOutsTilt1++;
00649 if (calibrationRoundCount < calibrationRounds-1)
00650 {
00651 calibrationState = calibrationStateDownTilt1;
00652 calibrationRoundCount++;
00653 }
00654 else
00655 {
00656
00657 speedNeckTilt /= calibrationSuccessfulRounds;
00658 calibrationSuccessfulRounds = 0;
00659 calibrationRoundCount = 0;
00660 calibrationState = calibrationStateDownTilt2;
00661 }
00662 }
00663 break;
00664 case calibrationStateDownTilt2:
00665 {
00666 Vector3<double> points[]={calibrationTilt2Down,calibrationTilt2Down};
00667 long durations[] = {1500,200};
00668 headPathPlanner.init(points,durations,sizeof(points)/sizeof(Vector3<double>),false);
00669 calibrationState = calibrationStateDownTilt2Wait;
00670 calibrationTime = SystemCall::getCurrentSystemTime();
00671 break;
00672 }
00673 case calibrationStateDownTilt2Wait:
00674 if (headPositionReached(calibrationTilt2Down) || isTimedOut())
00675 calibrationState = calibrationStateUpTilt2;
00676 break;
00677 case calibrationStateUpTilt2:
00678 {
00679 Vector3<double> points[]={calibrationTilt2Up};
00680 long durations[] = {0};
00681 headPathPlanner.init(points,durations,sizeof(points)/sizeof(Vector3<double>),false);
00682 calibrationState = calibrationStateUpTilt2Wait;
00683 calibrationTime = SystemCall::getCurrentSystemTime();
00684 break;
00685 }
00686 case calibrationStateUpTilt2Wait:
00687 if (headPositionReached(calibrationTilt2Up) || isTimedOut())
00688 {
00689 if (!isTimedOut())
00690 {
00691 speedHeadTilt += fabs(calibrationTilt2Down.z-calibrationTilt2Up.z) / (SystemCall::getTimeSince(calibrationTime)+0.0001);
00692 calibrationSuccessfulRounds++;
00693 }
00694 else
00695 calibrationTimeOutsTilt2++;
00696 if (calibrationRoundCount < calibrationRounds-1)
00697 {
00698 calibrationState = calibrationStateDownTilt2;
00699 calibrationRoundCount++;
00700 }
00701 else
00702 {
00703
00704 speedHeadTilt /= calibrationSuccessfulRounds;
00705 calibrationSuccessfulRounds = 0;
00706 calibrationRoundCount = 0;
00707 calibrationState = calibrationStateUseResults;
00708 }
00709 }
00710
00711 break;
00712 case calibrationStateUseResults:
00713 if ( calibrationTimeOutsTilt1 == 0
00714 && calibrationTimeOutsPan == 0
00715 && calibrationTimeOutsTilt2 == 0)
00716 {
00717 OUTPUT(idText,text,"Headspeed calibration was successful");
00718 }
00719 else
00720 {
00721 OUTPUT(idText,text,"Headspeed calibration failed. ");
00722 OUTPUT(idText,text,"Check the values of function headPositionReached or buy a new head !");
00723 OUTPUT(idText,text,"Rounds: " << calibrationRounds << "; Timeouts: Tilt1 = " << calibrationTimeOutsTilt1 << "; Pan = " << calibrationTimeOutsPan << "; Tilt2 = " << calibrationTimeOutsTilt2 );
00724 }
00725
00726 if (calibrationTimeOutsTilt1-calibrationRounds == 0) speedNeckTilt = 0.001500;
00727 if (calibrationTimeOutsPan-calibrationRounds == 0) speedHeadPan = 0.005350;
00728 if (calibrationTimeOutsTilt2-calibrationRounds == 0) speedHeadTilt = 0.002350;
00729
00730 OUTPUT(idText,text,"speedTilt1:" << speedNeckTilt);
00731 OUTPUT(idText,text,"speedPan:" << speedHeadPan);
00732 OUTPUT(idText,text,"speedTilt2:" << speedHeadTilt);
00733
00734
00735
00736 headPathPlanner.headPathSpeedNeckTilt = (double) speedNeckTilt;
00737 headPathPlanner.headPathSpeedHeadPan = (double) speedHeadPan;
00738 headPathPlanner.headPathSpeedHeadTilt = (double) speedHeadTilt;
00739 calibrationState = calibrationStateReady;
00740 break;
00741 default:
00742 case calibrationStateReady:
00743 break;
00744 }
00745 }
00746 }
00747
00748
00749
00750
00751
00752
00753
00754
00755
00756
00757
00758
00759
00760
00761
00762
00763
00764
00765
00766
00767
00768
00769
00770
00771
00772
00773
00774
00775
00776
00777
00778
00779
00780
00781
00782
00783
00784
00785
00786
00787
00788
00789
00790
00791
00792
00793
00794
00795
00796
00797
00798
00799
00800
00801
00802
00803
00804
00805
00806
00807
00808
00809
00810
00811
00812
00813
00814
00815
00816
00817
00818
00819
00820
00821
00822
00823
00824
00825
00826
00827
00828
00829