00001
00002
00003
00004
00005
00006
00007
00008 #include "Tools/FieldDimensions.h"
00009 #include "Tools/Player.h"
00010 #include "Tools/Math/Common.h"
00011 #include "Modules/ImageProcessor/ImageProcessorTools/ColorCorrector.h"
00012 #include "GT2004FlagSpecialist.h"
00013 #include "GT2004ImageProcessorTools.h"
00014
00015
00016 GT2004FlagSpecialist::GT2004FlagSpecialist(const ColorCorrector& colorCorrector) :
00017 colorCorrector(colorCorrector)
00018 {
00019 }
00020
00021 void GT2004FlagSpecialist::init(const Image& image)
00022 {
00023 for(int i = 0; i < 6; i++)
00024 {
00025 numberOfBoundingBoxes[i] = 0;
00026 }
00027 INIT_DEBUG_IMAGE(imageProcessorFlags, image);
00028 }
00029
00030 void GT2004FlagSpecialist::searchFlags
00031 (
00032 const Image& image,
00033 const ColorTable& colorTable,
00034 const CameraMatrix& cameraMatrix,
00035 colorClass color,
00036 bool pinkIsTop,
00037 const Geometry::Line horizonLine,
00038 int x, int y
00039 )
00040 {
00041 CameraInfo bwCameraInfo = image.cameraInfo;
00042 bwCameraInfo.resolutionHeight*=2;
00043 bwCameraInfo.resolutionWidth*=2;
00044 bwCameraInfo.focalLength*=2;
00045 bwCameraInfo.focalLengthInv/=2;
00046 bwCameraInfo.opticalCenter.x*=2;
00047 bwCameraInfo.opticalCenter.y*=2;
00048 bool gridPointIsCovered = false;
00049
00050
00051 DEBUG_IMAGE_SET_PIXEL_RED(imageProcessorFlags, x, y)
00052
00053 int i, j;
00054
00055 for(i = 0; i < 6; i++)
00056 {
00057 for(j = 0; j < numberOfBoundingBoxes[i]; j++)
00058 {
00059 if(x >= boundingBoxLeft[j][i] && x <= boundingBoxRight[j][i] &&
00060 y >= boundingBoxBottom[j][i] && y <= boundingBoxTop[j][i] )
00061 {
00062 gridPointIsCovered = true;
00063 }
00064 }
00065 }
00066
00067 if(gridPointIsCovered) return;
00068
00069 int pixelCounter = 0;
00070 int topPixelCounter = 0;
00071 int bottomPixelCounter = 0;
00072
00073 start.x = 2*x;
00074 start.y = 2*y;
00075
00076
00077 findEndOfFlag(image, bwCameraInfo, colorTable, start, horizonLine.direction,
00078 up, north, color, pinkIsTop, pinkIsTop, initial, pixelCounter, topPixelCounter, bottomPixelCounter);
00079
00080 findEndOfFlag(image, bwCameraInfo, colorTable, start, horizonLine.direction,
00081 down, south, color, pinkIsTop, pinkIsTop, initial, pixelCounter, topPixelCounter, bottomPixelCounter);
00082 DOT(imageProcessor_ball4, south.x/2, south.y/2, Drawings::black, Drawings::green);
00083
00084 findEndOfFlag(image, bwCameraInfo, colorTable, start, horizonLine.direction,
00085 right, east, color, pinkIsTop, pinkIsTop, initial, pixelCounter, topPixelCounter, bottomPixelCounter);
00086
00087 findEndOfFlag(image, bwCameraInfo, colorTable, start, horizonLine.direction,
00088 left, west, color, pinkIsTop, pinkIsTop, initial, pixelCounter, topPixelCounter, bottomPixelCounter);
00089
00090 DEBUG_IMAGE_SET_PIXEL_BLUE(imageProcessorFlags, north.x/2, north.y/2);
00091 DEBUG_IMAGE_SET_PIXEL_BLUE(imageProcessorFlags, east.x/2, east.y/2);
00092 DEBUG_IMAGE_SET_PIXEL_BLUE(imageProcessorFlags, south.x/2, south.y/2);
00093 DEBUG_IMAGE_SET_PIXEL_BLUE(imageProcessorFlags, west.x/2, west.y/2);
00094
00095 if(west == east)
00096 {
00097 Vector2<int> newStart((north.x + south.x)/2, (north.y + south.y)/2);
00098
00099 findEndOfFlag(image, bwCameraInfo, colorTable, newStart, horizonLine.direction,
00100 right, east, color, pinkIsTop, false, horizontal, pixelCounter, topPixelCounter, bottomPixelCounter);
00101
00102 findEndOfFlag(image, bwCameraInfo, colorTable, newStart, horizonLine.direction,
00103 left, west, color, pinkIsTop, false, horizontal, pixelCounter, topPixelCounter, bottomPixelCounter);
00104 }
00105
00106 start.x = (west.x + east.x) / 2;
00107 start.y = (west.y + east.y) / 2;
00108 DOT(imageProcessor_ball4, start.x/2, start.y/2, Drawings::black, Drawings::red);
00109 DOT(imageProcessor_ball4, east.x/2, east.y/2, Drawings::black, Drawings::yellow);
00110 DOT(imageProcessor_ball4, west.x/2, west.y/2, Drawings::black, Drawings::yellow);
00111
00112 DEBUG_IMAGE_SET_PIXEL_YELLOW(imageProcessorFlags, start.x/2, start.y/2);
00113
00114
00115 findEndOfFlag(image, bwCameraInfo, colorTable, start, horizonLine.direction,
00116 up, north, color, pinkIsTop, pinkIsTop, initial, pixelCounter, topPixelCounter, bottomPixelCounter);
00117
00118 findEndOfFlag(image, bwCameraInfo, colorTable, start, horizonLine.direction,
00119 down, south, color, pinkIsTop, pinkIsTop, initial, pixelCounter, topPixelCounter, bottomPixelCounter);
00120
00121 double distance = sqrt((double)sqr(south.x-north.x) + sqr(south.y-north.y));
00122
00123
00124 pixelCounter = 0;
00125 topPixelCounter = 0;
00126 bottomPixelCounter = 0;
00127
00128 double rightDist = 0.0;
00129 double leftDist = 0.0;
00130 int rightValidCounter = 0;
00131 int leftValidCounter = 0;
00132 int scans = 0;
00133
00134 Vector2<int> temp;
00135
00136 Vector2<int> lastStart;
00137 lastStart.x = 1000;
00138 lastStart.y = 1000;
00139
00140
00141 Vector2<double>step;
00142 step.x = (south.x - north.x) / (numberOfHorizontalScans + 1.0);
00143 step.y = (south.y - north.y) / (numberOfHorizontalScans + 1.0);
00144
00145 Geometry::Line leftVerticalLine;
00146 leftVerticalLine.base = horizonLine.base;
00147 leftVerticalLine.direction.x = -horizonLine.direction.y;
00148 leftVerticalLine.direction.y = horizonLine.direction.x;
00149
00150 bool pointIsGood;
00151 bool startIsInTop = true;
00152 for(i = 1; i <= numberOfHorizontalScans; i++)
00153 {
00154 if(i==(numberOfHorizontalScans + 1)/2)
00155 {
00156 startIsInTop = false;
00157
00158 continue;
00159 }
00160
00161 start.x = (int)(north.x + step.x * i);
00162 start.y = (int)(north.y + step.y * i);
00163 if ( start == lastStart ) continue;
00164 lastStart = start;
00165
00166 scans++;
00167
00168
00169 pointIsGood = findEndOfFlag(image, bwCameraInfo, colorTable, start, horizonLine.direction, right, temp,
00170 color, pinkIsTop, startIsInTop, horizontal, pixelCounter, topPixelCounter, bottomPixelCounter);
00171 double rightDistance = 0.5 + Geometry::getDistanceToLine(leftVerticalLine, Vector2<double>(temp.x,temp.y));
00172
00173 rightDist += rightDistance;
00174 if ( pointIsGood ) rightValidCounter++;
00175
00176
00177 pointIsGood = findEndOfFlag(image, bwCameraInfo, colorTable, start, horizonLine.direction, left, temp,
00178 color, pinkIsTop, startIsInTop, horizontal, pixelCounter, topPixelCounter, bottomPixelCounter);
00179 double leftDistance = -0.5 + Geometry::getDistanceToLine(leftVerticalLine, Vector2<double>(temp.x,temp.y));
00180
00181 leftDist += leftDistance;
00182 if ( pointIsGood ) leftValidCounter++;
00183 }
00184
00185 rightDist = rightDist / scans;
00186 bool rightValid = (double)rightValidCounter >= scans / 2;
00187 leftDist = leftDist / scans;
00188 bool leftValid = (double)leftValidCounter >= scans / 2;
00189
00190 distance = sqrt((double)sqr(east.x-west.x) + sqr(east.y-west.y));
00191
00192
00193 step.x = (east.x - west.x) / (numberOfVerticalScans + 1.0);
00194 step.y = (east.y - west.y) / (numberOfVerticalScans + 1.0);
00195
00196 double topDist = 0.0;
00197 double bottomDist = 0.0;
00198 int topValidCounter = 0;
00199 int bottomValidCounter = 0;
00200 scans = 0;
00201 lastStart.x = 1000;
00202 lastStart.y = 1000;
00203
00204 for(i = 1; i <= numberOfVerticalScans; i++)
00205 {
00206 start.x = (int)(west.x + step.x * i);
00207 start.y = (int)(west.y + step.y * i);
00208
00209 if ( start == lastStart ) continue;
00210 lastStart = start;
00211
00212 scans++;
00213
00214
00215 pointIsGood = findEndOfFlag(image, bwCameraInfo, colorTable, start, horizonLine.direction, up, north,
00216 color, pinkIsTop, pinkIsTop, vertical, pixelCounter, topPixelCounter, bottomPixelCounter);
00217 topDist += 0.5 + Geometry::getDistanceToLine(horizonLine, Vector2<double>(north.x,north.y));
00218 if ( pointIsGood ) topValidCounter++;
00219
00220
00221 pointIsGood = findEndOfFlag(image, bwCameraInfo, colorTable, start, horizonLine.direction, down, south,
00222 color, pinkIsTop, pinkIsTop, vertical, pixelCounter, topPixelCounter, bottomPixelCounter);
00223 bottomDist += -0.5 + Geometry::getDistanceToLine(horizonLine, Vector2<double>(south.x,south.y));
00224 if ( pointIsGood ) bottomValidCounter++;
00225 }
00226
00227 topDist = topDist / scans;
00228 bool topValid = (double)topValidCounter >= scans / 2;
00229 bottomDist = bottomDist / scans;
00230 bool bottomValid = (double)bottomValidCounter >= scans / 2;
00231
00232 double topRatio = (double)topPixelCounter / (double)pixelCounter;
00233 double bottomRatio = (double)bottomPixelCounter / (double)pixelCounter;
00234
00235 if (topRatio > 0.2 && bottomRatio > 0.2)
00236 {
00237 Flag::FlagType flagType = Flag::pinkAboveYellow;
00238 switch(color)
00239 {
00240 case yellow: flagType = pinkIsTop ? Flag::pinkAboveYellow : Flag::yellowAbovePink; break;
00241
00242 case skyblue: flagType = pinkIsTop ? Flag::pinkAboveSkyblue : Flag::skyblueAbovePink; break;
00243 }
00244
00245 int i = numberOfBoundingBoxes[flagType];
00246
00247 boundingBoxLeft[i][flagType] = leftDist;
00248 boundingBoxRight[i][flagType] = rightDist;
00249 boundingBoxTop[i][flagType] = topDist;
00250 boundingBoxBottom[i][flagType] = bottomDist;
00251
00252 boundingBoxLeftValid[i][flagType] = leftValid;
00253 boundingBoxRightValid[i][flagType] = rightValid;
00254 boundingBoxTopValid[i][flagType] = topValid;
00255 boundingBoxBottomValid[i][flagType] = bottomValid;
00256
00257 numberOfBoundingBoxes[flagType]++;
00258 if(numberOfBoundingBoxes[flagType] >= maxNumberOfBoundingBoxes)
00259 {
00260 numberOfBoundingBoxes[flagType] = maxNumberOfBoundingBoxes - 1;
00261 }
00262
00263 DEBUG_IMAGE_SET_PIXEL_GREEN(imageProcessorFlags, north.x/2, north.y/2);
00264 DEBUG_IMAGE_SET_PIXEL_GREEN(imageProcessorFlags, east.x/2, east.y/2);
00265 DEBUG_IMAGE_SET_PIXEL_GREEN(imageProcessorFlags, south.x/2, south.y/2);
00266 DEBUG_IMAGE_SET_PIXEL_GREEN(imageProcessorFlags, west.x/2, west.y/2);
00267 }
00268 }
00269
00270 bool GT2004FlagSpecialist::findEndOfFlag
00271 (
00272 const Image& image,
00273 const CameraInfo& bwCameraInfo,
00274 const ColorTable& colorTable,
00275 const Vector2<int> start,
00276 Vector2<double> horizonDirection,
00277 Direction directionToGo,
00278 Vector2<int>& destination,
00279 colorClass color,
00280 bool pinkIsTop,
00281 bool startIsInTop,
00282 DebugType type,
00283 int& countPixel,
00284 int& countTop,
00285 int& countBottom
00286 )
00287 {
00288 bool valid = true;
00289 int counter = 0;
00290 int blackCounter = 0;
00291 int outsideCounter = 0;
00292 colorClass current, expected, allowed;
00293 colorClass topColor = pink;
00294 colorClass bottomColor = pink;
00295 colorClass startColor;
00296
00297 if(pinkIsTop) bottomColor = color; else topColor = color;
00298 if(startIsInTop) startColor = topColor; else startColor = bottomColor;
00299
00300 switch(directionToGo)
00301 {
00302 case left:
00303 case right:
00304 default:
00305 expected = startColor;
00306 allowed = startColor;
00307 break;
00308 case up:
00309 expected = topColor;
00310 allowed = bottomColor;
00311 break;
00312 case down:
00313 expected = bottomColor;
00314 allowed = topColor;
00315 break;
00316 }
00317
00318 destination = start;
00319
00320
00321 Vector2<int> lastInsideFlag, lastDestination;
00322 lastInsideFlag = start;
00323
00324 Vector2<double> direction;
00325 switch(directionToGo)
00326 {
00327 case up:
00328 direction.x = horizonDirection.y;
00329 direction.y = -horizonDirection.x;
00330 break;
00331 case right:
00332 direction = horizonDirection;
00333 break;
00334 case down:
00335 direction.x = -horizonDirection.y;
00336 direction.y = horizonDirection.x;
00337 break;
00338 case left:
00339 direction.x = -horizonDirection.x;
00340 direction.y = -horizonDirection.y;
00341 break;
00342 }
00343 enum {incX, decX, incY, decY} mode;
00344 if(direction.y < -fabs(direction.x)) mode = decY;
00345 else if(direction.y > fabs(direction.x)) mode = incY;
00346 else if(direction.x < -fabs(direction.y)) mode = decX;
00347 else mode = incX;
00348
00349 Vector2<int> diff;
00350
00351 bool goOn = true;
00352 while(goOn)
00353 {
00354 counter++;
00355
00356
00357 switch(mode)
00358 {
00359 case incX:
00360 diff.x++;
00361 diff.y = (int)(diff.x * direction.y / direction.x);
00362 break;
00363 case decX:
00364 diff.x--;
00365 diff.y = (int)(diff.x * direction.y / direction.x);
00366 break;
00367 case incY:
00368 diff.y++;
00369 diff.x = (int)(diff.y * direction.x / direction.y);
00370 break;
00371 case decY:
00372 diff.y--;
00373 diff.x = (int)(diff.y * direction.x / direction.y);
00374 break;
00375 }
00376 lastDestination = destination;
00377 destination = start + diff;
00378
00379
00380 if ( type == initial )
00381 {
00382 DEBUG_IMAGE_SET_PIXEL_Y(imageProcessorFlags, destination.x/2, destination.y/2, 180)
00383 }
00384 if ( type == horizontal )
00385 {
00386 DEBUG_IMAGE_SET_PIXEL_Y(imageProcessorFlags, destination.x/2, destination.y/2, 90)
00387 }
00388 if ( type == vertical )
00389 {
00390 DEBUG_IMAGE_SET_PIXEL_Y(imageProcessorFlags, destination.x/2, destination.y/2, 0)
00391 }
00392
00393 if(destination.x < 1 || destination.x >= bwCameraInfo.resolutionWidth - 1 ||
00394 destination.y < 1 || destination.y >= bwCameraInfo.resolutionHeight - 2)
00395 {
00396 valid = outsideCounter > 10;
00397 goOn = false;
00398 destination = lastInsideFlag;
00399 }
00400 else
00401 {
00402 current = CORRECTED_COLOR_CLASS(
00403 destination.x/2,
00404 destination.y/2,
00405 image.getHighResY(destination.x,destination.y),
00406 image.image[destination.y/2][1][destination.x/2],
00407 image.image[destination.y/2][2][destination.x/2]);
00408
00409 if(current == expected)
00410 {
00411 lastInsideFlag = destination;
00412 outsideCounter = 0;
00413 }
00414 else if(current != allowed)
00415 {
00416 blackCounter++;
00417 outsideCounter++;
00418 if(blackCounter > 20)
00419 {
00420 goOn = false;
00421 destination = lastInsideFlag;
00422 }
00423 }
00424
00425 if(current == topColor) countTop++;
00426 else if(current == bottomColor) countBottom++;
00427
00428 }
00429 }
00430
00431 DEBUG_IMAGE_SET_PIXEL_RED(imageProcessorFlags, destination.x/2, destination.y/2)
00432
00433 countPixel += counter - outsideCounter;
00434
00435 return valid;
00436 }
00437
00438 void GT2004FlagSpecialist::getFlagPercept
00439 (
00440 const CameraMatrix& cameraMatrix,
00441 const CameraMatrix& prevCameraMatrix,
00442 const CameraInfo& cameraInfo,
00443 const Geometry::Line horizonLine,
00444 LandmarksPercept& landmarksPercept
00445 )
00446 {
00447 CameraInfo bwCameraInfo = cameraInfo;
00448 bwCameraInfo.resolutionHeight*=2;
00449 bwCameraInfo.resolutionWidth*=2;
00450 bwCameraInfo.focalLength*=2;
00451 bwCameraInfo.focalLengthInv/=2;
00452 bwCameraInfo.opticalCenter.x*=2;
00453 bwCameraInfo.opticalCenter.y*=2;
00454 int flip = getPlayer().getTeamColor() == Player::blue ? -1 : 1;
00455
00456 Vector2<double> verticalDirection;
00457 verticalDirection.x = -horizonLine.direction.y;
00458 verticalDirection.y = horizonLine.direction.x;
00459
00460
00461 double factor = bwCameraInfo.focalLength;
00462 for(int flagType = 0; flagType < 6; flagType++)
00463 {
00464
00465 for(int i = 0; i < numberOfBoundingBoxes[flagType]; i++)
00466 {
00467 }
00468 bestBoundingBox[flagType] = 0;
00469
00470 if(numberOfBoundingBoxes[flagType] > 0)
00471 {
00472 Vector2<double> right, left, top, bottom;
00473
00474 right = horizonLine.base +
00475 horizonLine.direction * boundingBoxRight[bestBoundingBox[flagType]][flagType]
00476 - verticalDirection *
00477 (boundingBoxTop[bestBoundingBox[flagType]][flagType] +
00478 boundingBoxBottom[bestBoundingBox[flagType]][flagType]
00479 ) / 2;
00480
00481 left = horizonLine.base +
00482 horizonLine.direction * boundingBoxLeft[bestBoundingBox[flagType]][flagType]
00483 - verticalDirection *
00484 (boundingBoxTop[bestBoundingBox[flagType]][flagType] +
00485 boundingBoxBottom[bestBoundingBox[flagType]][flagType]
00486 ) / 2;
00487
00488 top = horizonLine.base
00489 - verticalDirection * boundingBoxTop[bestBoundingBox[flagType]][flagType]
00490 + horizonLine.direction *
00491 (boundingBoxLeft[bestBoundingBox[flagType]][flagType] +
00492 boundingBoxRight[bestBoundingBox[flagType]][flagType]
00493 ) / 2;
00494
00495 bottom = horizonLine.base
00496 - verticalDirection * boundingBoxBottom[bestBoundingBox[flagType]][flagType]
00497 + horizonLine.direction *
00498 (boundingBoxLeft[bestBoundingBox[flagType]][flagType] +
00499 boundingBoxRight[bestBoundingBox[flagType]][flagType]
00500 ) / 2;
00501
00502
00503 Vector3<double> vectorToLeft(factor,
00504 bwCameraInfo.opticalCenter.x - left.x,
00505 bwCameraInfo.opticalCenter.y - left.y);
00506 Vector3<double> vectorToRight(factor,
00507 bwCameraInfo.opticalCenter.x - right.x,
00508 bwCameraInfo.opticalCenter.y - right.y);
00509 Vector3<double> vectorToTop(factor,
00510 bwCameraInfo.opticalCenter.x - top.x,
00511 bwCameraInfo.opticalCenter.y - top.y);
00512 Vector3<double> vectorToBottom(factor,
00513 bwCameraInfo.opticalCenter.x - bottom.x,
00514 bwCameraInfo.opticalCenter.y - bottom.y);
00515
00516
00517 Vector3<double>
00518 vectorToLeftWorld = Geometry::rayFromCamera(int(left.y / 2), cameraMatrix, prevCameraMatrix, vectorToLeft, cameraInfo),
00519 vectorToRightWorld = Geometry::rayFromCamera(int(right.y / 2), cameraMatrix, prevCameraMatrix, vectorToRight, cameraInfo),
00520 vectorToTopWorld = Geometry::rayFromCamera(int(top.y / 2), cameraMatrix, prevCameraMatrix, vectorToTop, cameraInfo),
00521 vectorToBottomWorld = Geometry::rayFromCamera(int(bottom.y / 2), cameraMatrix, prevCameraMatrix, vectorToBottom, cameraInfo);
00522
00523 double
00524 leftAngle = atan2(vectorToLeftWorld.y,vectorToLeftWorld.x),
00525 rightAngle = atan2(vectorToRightWorld.y,vectorToRightWorld.x),
00526 topAngle = atan2(vectorToTopWorld.z,sqrt((double)sqr(vectorToTopWorld.x) + sqr(vectorToTopWorld.y)) ),
00527 bottomAngle = atan2(vectorToBottomWorld.z,sqrt((double)sqr(vectorToBottomWorld.x) + sqr(vectorToBottomWorld.y)) );
00528
00529
00530 Vector2<double>flagPosition;
00531
00532 switch (flagType)
00533 {
00534 case Flag::pinkAboveYellow:
00535 flagPosition.x = xPosBackFlags * flip;
00536 flagPosition.y = yPosRightFlags * flip;
00537 break;
00538 case Flag::pinkAboveSkyblue:
00539 flagPosition.x = xPosFrontFlags * flip;
00540 flagPosition.y = yPosRightFlags * flip;
00541 break;
00542 case Flag::yellowAbovePink:
00543 flagPosition.x = xPosBackFlags * flip;
00544 flagPosition.y = yPosLeftFlags * flip;
00545 break;
00546 case Flag::skyblueAbovePink:
00547 flagPosition.x = xPosFrontFlags * flip;
00548 flagPosition.y = yPosLeftFlags * flip;
00549 break;
00550 }
00551 ConditionalBoundary boundary;
00552 boundary.addX(leftAngle,!boundingBoxLeftValid[bestBoundingBox[flagType]][flagType]);
00553 boundary.addX(rightAngle,!boundingBoxRightValid[bestBoundingBox[flagType]][flagType]);
00554 boundary.addY(topAngle,!boundingBoxTopValid[bestBoundingBox[flagType]][flagType]);
00555 boundary.addY(bottomAngle,!boundingBoxBottomValid[bestBoundingBox[flagType]][flagType]);
00556 landmarksPercept.addFlag((Flag::FlagType)flagType, flagPosition, boundary);
00557 }
00558 }
00559 Vector2<double> cameraOffset(cameraMatrix.translation.x,
00560 cameraMatrix.translation.y);
00561
00562 estimateOffsetForFlags(landmarksPercept, cameraOffset);
00563 SEND_DEBUG_IMAGE(imageProcessorFlags);
00564 }
00565
00566 void GT2004FlagSpecialist::estimateOffsetForFlags
00567 (
00568 LandmarksPercept& landmarksPercept,
00569 const Vector2<double>& cameraOffset
00570 )
00571 {
00572 for(int i = 0;i < landmarksPercept.numberOfFlags; ++i)
00573 {
00574 Flag& flag = landmarksPercept.flags[i];
00575
00576
00577 double distance;
00578 double direction = flag.x.getCenter();
00579
00580 if(!flag.isOnBorder(flag.y.min) && !flag.isOnBorder(flag.y.max))
00581 {
00582 if(flag.y.min != flag.y.max)
00583 {
00584 distance = flagHeight / (tan(flag.y.max) - tan(flag.y.min)) + flagRadius;
00585 flag.distanceValidity = 0.8;
00586 }
00587 else
00588 {
00589 distance = 4500;
00590 flag.distanceValidity = 0.05;
00591 }
00592 }
00593 else
00594 {
00595 distance = flagRadius / sin(flag.x.getSize() / 2);
00596 if(!flag.isOnBorder(flag.x.min) && !flag.isOnBorder(flag.x.max))
00597 flag.distanceValidity = 0.7;
00598 else
00599 flag.distanceValidity = 0.2;
00600 }
00601 if(!flag.isOnBorder(flag.x.min) && !flag.isOnBorder(flag.x.max))
00602 flag.angleValidity = 0.8;
00603 else
00604 flag.angleValidity = 0.7;
00605
00606 Pose2D p = Pose2D(cameraOffset) + Pose2D(direction)
00607 + Pose2D(Vector2<double>(distance,0));
00608 flag.distance = p.translation.abs();
00609 flag.angle = direction;
00610 if (flag.distance > 6000)
00611 {
00612 flag.distance = 6000;
00613 flag.distanceValidity=0;
00614 }
00615 else if (flag.distance > 3000)
00616 flag.distanceValidity*=0.5;
00617 }
00618 }
00619
00620
00621
00622
00623
00624
00625
00626
00627
00628
00629
00630
00631
00632
00633
00634
00635
00636
00637
00638
00639
00640
00641
00642
00643
00644
00645
00646
00647
00648
00649
00650
00651
00652
00653
00654
00655
00656
00657
00658
00659
00660
00661
00662
00663