Main Page | Namespace List | Class Hierarchy | Alphabetical List | Class List | File List | Namespace Members | Class Members | File Members | Related Pages

Geometry Class Reference

The class Geometry defines representations for geometric objects and Methods for calculations with such object. More...

#include <Geometry.h>

Collaboration diagram for Geometry:

Collaboration graph
[legend]
List of all members.

Static Public Member Functions

double angleTo (const Pose2D &from, const Vector2< double > &to)
 Calculates the angle between a pose and a position.

double distanceTo (const Pose2D &from, const Vector2< double > &to)
 Calculates the distance from a pose to a position.

Vector2< double > vectorTo (const Pose2D &from, const Vector2< double > &to)
 Calculates the relative vector from a pose to a position.

Circle getCircle (const Vector2< int > point1, const Vector2< int > point2, const Vector2< int > point3)
 Returns the circle defined by the three points.

bool getIntersectionOfLines (const Line line1, const Line line2, Vector2< double > &intersection)
bool getIntersectionOfLines (const Line line1, const Line line2, Vector2< int > &intersection)
bool getIntersectionOfRaysFactor (const Line ray1, const Line ray2, double &intersection)
double getDistanceToLine (const Line line, const Vector2< double > &point)
double getDistanceToEdge (const Line line, const Vector2< double > &point)
double distance (const Vector2< double > &point1, const Vector2< double > &point2)
double distance (const Vector2< int > &point1, const Vector2< int > &point2)
Vector3< double > rayFromCamera (int y, const CameraMatrix &cameraMatrix, const CameraMatrix &prevCameraMatrix, const Vector3< double > vector, const CameraInfo &cameraInfo)
void calculateAnglesForPoint (const Vector2< int > &point, const CameraMatrix &cameraMatrix, const CameraInfo &cameraInfo, Vector2< double > &angles)
void calculateAnglesForPoint (const Vector2< int > &point, const CameraMatrix &cameraMatrix, const CameraMatrix &prevCameraMatrix, const CameraInfo &cameraInfo, Vector2< double > &angles)
void calculatePointByAngles (const Vector2< double > &angles, const CameraMatrix &cameraMatrix, const CameraInfo &cameraInfo, Vector2< int > &point)
bool clipLineWithQuadrangle (const Line lineToClip, const Vector2< double > &corner0, const Vector2< double > &corner1, const Vector2< double > &corner2, const Vector2< double > &corner3, Vector2< double > &clipPoint1, Vector2< double > &clipPoint2)
bool clipLineWithQuadrangle (const Line lineToClip, const Vector2< double > &corner0, const Vector2< double > &corner1, const Vector2< double > &corner2, const Vector2< double > &corner3, Vector2< int > &clipPoint1, Vector2< int > &clipPoint2)
bool isPointInsideRectangle (const Vector2< double > &bottomLeftCorner, const Vector2< double > &topRightCorner, const Vector2< double > &point)
bool isPointInsideRectangle (const Vector2< int > &bottomLeftCorner, const Vector2< int > &topRightCorner, const Vector2< int > &point)
bool clipPointInsideRectange (const Vector2< int > &bottomLeftCorner, const Vector2< int > &topRightCorner, Vector2< int > &point)
bool calculatePointOnField (const int x, const int y, const CameraMatrix &cameraMatrix, const CameraInfo &cameraInfo, Vector2< int > &pointOnField)
 Calculates where a pixel in the image lies on the ground (relative to the robot).

bool calculatePointOnField (const int x, const int y, const CameraMatrix &cameraMatrix, const CameraMatrix &prevCameraMatrix, const CameraInfo &cameraInfo, Vector2< int > &pointOnField)
 Calculates where a pixel in the image lies on the ground (relative to the robot).

void calculatePointInImage (const Vector2< int > &point, const CameraMatrix &cameraMatrix, const CameraInfo &cameraInfo, Vector2< int > &pointInImage)
 Calculates where a relative point on the ground appears in an image.

bool getIntersectionPointsOfLineAndRectangle (const Vector2< int > &bottomLeft, const Vector2< int > &topRight, const Geometry::Line line, Vector2< int > &point1, Vector2< int > &point2)
 Clips a line with a rectangle.

bool clipLineWithRectangleCohenSutherland (const Vector2< int > &bottomLeft, const Vector2< int > &topRight, Vector2< int > &point1, Vector2< int > &point2)
 Clips a line with the Cohen-Sutherland-Algorithm.

int cohenSutherlandOutCode (const Vector2< int > &bottomLeft, const Vector2< int > &topRight, Vector2< int > &point)
 Calculates the Cohen Sutherland Code for a given point and a given rectangle.

int intersection (int a1, int b1, int a2, int b2, int value)
 Calculates the intersection of an arbitrary line and a horizontal or vertical line.

Vector2< double > relative2FieldCoord (RobotPose rp, double x, double y)
 Function does the transformation from 2d relative robot coordinates to absolute field coordinates.

Vector2< double > fieldCoord2Relative (RobotPose robotPose, Vector2< double > fieldCoord)
 Function does the transformation from 2d field coordinates to coordinates relative to the robot.

bool calculateBallInImage (const Vector2< double > &ballOffset, const CameraMatrix &cameraMatrix, const CameraInfo &cameraInfo, Circle &circle)
 The function approximates the shape of a ball in the camera image.

double getDistanceBySize (const CameraInfo &cameraInfo, double sizeInReality, double sizeInPixels)
double getDistanceBySize (const CameraInfo &cameraInfo, double sizeInReality, double sizeInPixels, int centerX, int centerY)
 The function determines how far an object is away depending on its real size and the size in the image along with its center position, using camera intrinsic parameters.

double getDistanceByAngleSize (double sizeInReality, double sizeInPixels)
 The function determines how far an object is away depending on its real size and the size in the image.

double getBallDistanceByAngleSize (double sizeInReality, double sizeInPixels)
 The function determines how far the ball is away depending on its real size and the size in the image.

double getSizeByDistance (double sizeInReality, double distance, double imageWidthPixels, double imageWidthAngle)
 The function determines how big an object appears in the image depending on its distance and size.

double getSizeByDistance (const CameraInfo &cameraInfo, double sizeInReality, double distance)
 The function determines how big an object appears in the image depending on its distance and size.

Geometry::Line calculateHorizon (const CameraMatrix &cameraMatrix, const CameraInfo &cameraInfo)
 The function calculates the horizon.

int calculateLineSize (const Vector2< int > &pointInImage, const CameraMatrix &cameraMatrix, const CameraInfo &cameraInfo)
 The function calculates the expected size (pixel) of a field line in an image.

double pixelSizeToAngleSize (double pixelSize, const CameraInfo &cameraInfo)
 Calculates the angle size for a given pixel size.

double angleSizeToPixelSize (double angleSize, const CameraInfo &cameraInfo)
 Calculates the pixel size for a given angle size.

void radialDistortionCorrection (const CameraInfo &cameraInfo, const int srcX, const int srcY, double &correctedX, double &correctedY)
 Corrects the radial distortion introduced by the camera lens (using a 4th order model) of a given pixel.

void setupRadialCorrection (const CameraInfo &cameraInfo)
 This function builds a radial distortion correction look-up table based on the parameters contained in cameraInfo.

void setupRadialCorrectionERS7 ()
void setupRadialCorrectionERS210 ()
bool insideCircle (Geometry::Circle &circle, double radius2, double x, double y)
void radialDistortionCorrectionFast (const int srcX, const int srcY, int &correctedX, int &correctedY)
 Corrects the radial distortion introduced by the camera lens (using a 4th order model) of a given pixel, using a pre-computed look-up table.


Static Private Member Functions

double calculateScaleFactor (int y, unsigned long frameNumber, unsigned long prevFrameNumber, const CameraInfo &cameraInfo)

Static Private Attributes

CorrectedCoords radialCorrectionLUT [cameraResolutionHeight_ERS7][cameraResolutionWidth_ERS7]

Detailed Description

The class Geometry defines representations for geometric objects and Methods for calculations with such object.

Definition at line 26 of file Geometry.h.


Member Function Documentation

double Geometry::angleTo const Pose2D from,
const Vector2< double > &  to
[static]
 

Calculates the angle between a pose and a position.

Parameters:
from The base pose.
to The other position.
Returns:
the angle from the pose to the position.

Definition at line 18 of file Geometry.cpp.

References Pose2D::translation, Vector2< double >::x, and Vector2< double >::y.

Referenced by GT2004ObstaclesLocator::addPSDPercept(), MathFunctions::angleTo(), AngleSymbols::calculateCombinedAngles(), AngleSymbols::calculateLocalisationBasedAngles(), GT2004StrategySymbols::estimateTimeToReachBall(), GT2004BasicBehaviorDirectedScanForLandmarks::execute(), GT2004BasicBehaviorGoToPoint::execute(), GT2004BasicBehaviorGoToPointAndAvoidObstacles::execute(), GT2004BasicBehaviorGoForwardToPoint::execute(), GT2004BasicBehaviorTurnAroundPoint::execute(), GT2004BasicBehaviorGoaliePositionReturn::execute(), GT2004BasicBehaviorGoaliePosition::execute(), GT2004BasicBehaviorGoToBallWithoutTurning::execute(), GT2004BasicBehaviorGoToBall::execute(), GT2004BasicBehaviorEvolveOmniParameters::execute(), and fieldCoord2Relative().

double Geometry::distanceTo const Pose2D from,
const Vector2< double > &  to
[static]
 

Calculates the distance from a pose to a position.

Parameters:
from The base pose.
to The other position.
Returns:
the distance from the pose to the position.

Definition at line 25 of file Geometry.cpp.

Referenced by MathFunctions::distanceTo(), GT2004StrategySymbols::estimateTimeToReachBall(), KickLogger::execute(), GT2004BasicBehaviorGoToPoint::execute(), GT2004BasicBehaviorGoToPointAndAvoidObstacles::execute(), GT2004BasicBehaviorTurnAroundPoint::execute(), GT2004BasicBehaviorGoaliePositionReturn::execute(), GT2004BasicBehaviorGoToBallWithoutTurning::execute(), GT2004BasicBehaviorGoToBall::execute(), GT2004BasicBehaviorEvolveOmniParameters::execute(), fieldCoord2Relative(), KickLogger::getBallX(), KickLogger::getBallY(), RobotPoseSymbols::getDistanceToOpponentGoal(), RobotPoseSymbols::getDistanceToOwnGoal(), GT2004StrategySymbols::getGoalieMaxPositionSpeed(), BallSymbols::getKnownDistance(), GT2004HeadControlSymbols::getSeenDistance(), BallSymbols::getSeenDistance(), KickSelectionSymbols::retrieveKick(), GT2004BallLocator::setBallStateV2(), and ObstaclesSymbols::update().

Vector2< double > Geometry::vectorTo const Pose2D from,
const Vector2< double > &  to
[static]
 

Calculates the relative vector from a pose to a position.

Parameters:
from The base pose.
to The other position.
Returns:
the vector from the pose to the position.

Definition at line 31 of file Geometry.cpp.

Geometry::Circle Geometry::getCircle const Vector2< int >  point1,
const Vector2< int >  point2,
const Vector2< int >  point3
[static]
 

Returns the circle defined by the three points.

Parameters:
point1 The first point.
point2 The second point.
point3 The third point.
Returns:
The circle defined by point1, point2 and point3.

Definition at line 45 of file Geometry.cpp.

References Geometry::Circle::center, Geometry::Circle::radius, sqr, Vector2< double >::x, and Vector2< double >::y.

Referenced by RBallSpecialist2::calculateCircleByEdges(), and RBallSpecialist2::calculateSmallCircle().

bool Geometry::getIntersectionOfLines const Line  line1,
const Line  line2,
Vector2< double > &  intersection
[static]
 

Definition at line 129 of file Geometry.cpp.

References intersection().

Referenced by RFieldSpecialist::analyzeLines(), FieldDimensions::clipLineWithField(), clipLineWithQuadrangle(), RBridgeSpecialist::createBBox(), BoxSpecialist::createBBox(), getIntersectionOfLines(), BoxSpecialist::mergeBoxes(), RDefaultStrategy::postScan(), GT2004ImageProcessor::scanColumns(), and BoxSpecialist::searchGoal().

Here is the call graph for this function:

bool Geometry::getIntersectionOfLines const Line  line1,
const Line  line2,
Vector2< int > &  intersection
[static]
 

Definition at line 115 of file Geometry.cpp.

References getIntersectionOfLines(), intersection(), Vector2< V >::x, and Vector2< V >::y.

Here is the call graph for this function:

bool Geometry::getIntersectionOfRaysFactor const Line  ray1,
const Line  ray2,
double &  intersection
[static]
 

Definition at line 166 of file Geometry.cpp.

double Geometry::getDistanceToLine const Line  line,
const Vector2< double > &  point
[static]
 

Definition at line 189 of file Geometry.cpp.

References distance(), Vector2< V >::normalize(), point, Vector2< V >::x, and Vector2< V >::y.

Referenced by RBallSpecialist2::addBallPercept(), REnemySpecialist::calculateFarestPoint(), REnemySpecialist::calculateFarestPointCOG(), REnemySpecialist::calculateFarestPointFastCOG(), FieldDimensions::clipLineWithField(), BoxSpecialist::fusionGoal(), RFieldSpecialist::fusionLines(), getDistanceToEdge(), FieldDimensions::isInsideField(), BoxSpecialist::mergeBoxes(), GT2004FlagSpecialist::searchFlags(), BoxSpecialist::searchGoal(), FieldDimensions::vectorToBorder(), and FieldDimensions::vectorToBorderIncludingGoals().

Here is the call graph for this function:

double Geometry::getDistanceToEdge const Line  line,
const Vector2< double > &  point
[static]
 

Definition at line 208 of file Geometry.cpp.

References distance(), getDistanceToLine(), and point.

Here is the call graph for this function:

double Geometry::distance const Vector2< double > &  point1,
const Vector2< double > &  point2
[static]
 

Definition at line 230 of file Geometry.cpp.

Referenced by GT2004BallSpecialist::checkIfPointsAreInsideBall(), REnemySpecialist::executePostProcessing(), RFieldSpecialist::fusionLines(), getDistanceToEdge(), getDistanceToLine(), RasterSpecialist::getDistanceToLine(), GT2004EdgeSpecialist::getEdgesPercept(), and getMin().

double Geometry::distance const Vector2< int > &  point1,
const Vector2< int > &  point2
[static]
 

Definition at line 239 of file Geometry.cpp.

double Geometry::calculateScaleFactor int  y,
unsigned long  frameNumber,
unsigned long  prevFrameNumber,
const CameraInfo cameraInfo
[static, private]
 

Definition at line 247 of file Geometry.cpp.

References getRobotConfiguration(), RobotConfiguration::getRobotDimensions(), RobotDimensions::imagesPerSecond, RobotDimensions::motionCycleTime, and CameraInfo::resolutionHeight.

Referenced by rayFromCamera().

Here is the call graph for this function:

Vector3< double > Geometry::rayFromCamera int  y,
const CameraMatrix cameraMatrix,
const CameraMatrix prevCameraMatrix,
const Vector3< double >  vector,
const CameraInfo cameraInfo
[static]
 

Definition at line 265 of file Geometry.cpp.

References calculateScaleFactor(), CameraMatrix::frameNumber, Pose3D::rotation, and CameraInfo::simulated.

Referenced by GT2004FlagSpecialist::getFlagPercept().

Here is the call graph for this function:

void Geometry::calculateAnglesForPoint const Vector2< int > &  point,
const CameraMatrix cameraMatrix,
const CameraInfo cameraInfo,
Vector2< double > &  angles
[static]
 

Definition at line 284 of file Geometry.cpp.

References point, sqr, Vector3< V >::x, Vector2< int >::x, Vector3< V >::y, Vector2< int >::y, and Vector3< V >::z.

Referenced by RBallSpecialist2::addBallPercept(), GT2004BallSpecialist::addBallPercept(), GoalRecognizer::calculateVerticalGoalScanLines(), GT2004GoalRecognizer::calculateVerticalGoalScanLines(), BoxSpecialist::detectFreePartOfGoal(), GoalRecognizer::ColoredPartsCheck::determineLargePart(), GT2004GoalRecognizer::ColoredPartsCheck::determineLargePart(), GoalRecognizer::scanLinesForGoals(), and GT2004GoalRecognizer::scanLinesForGoals().

void Geometry::calculateAnglesForPoint const Vector2< int > &  point,
const CameraMatrix cameraMatrix,
const CameraMatrix prevCameraMatrix,
const CameraInfo cameraInfo,
Vector2< double > &  angles
[static]
 

Definition at line 312 of file Geometry.cpp.

References point, and Vector2< int >::y.

void Geometry::calculatePointByAngles const Vector2< double > &  angles,
const CameraMatrix cameraMatrix,
const CameraInfo cameraInfo,
Vector2< int > &  point
[static]
 

Definition at line 331 of file Geometry.cpp.

References RotationMatrix::invert(), point, Vector2< int >::x, Vector3< V >::x, Vector2< int >::y, Vector3< V >::y, and Vector3< V >::z.

Referenced by calculateBallInImage(), GoalRecognizer::calculateVerticalGoalScanLines(), GT2004GoalRecognizer::calculateVerticalGoalScanLines(), GoalRecognizer::scanHorizontalForGoals(), GT2004GoalRecognizer::scanHorizontalForGoals(), and GoalRecognizer::scanLinesForGoals().

Here is the call graph for this function:

bool Geometry::clipLineWithQuadrangle const Line  lineToClip,
const Vector2< double > &  corner0,
const Vector2< double > &  corner1,
const Vector2< double > &  corner2,
const Vector2< double > &  corner3,
Vector2< double > &  clipPoint1,
Vector2< double > &  clipPoint2
[static]
 

Definition at line 379 of file Geometry.cpp.

References Geometry::Line::base, Geometry::Line::direction, getIntersectionOfLines(), point, Vector2< int >::x, Vector2< V >::x, Vector2< double >::x, Vector2< int >::y, Vector2< V >::y, and Vector2< double >::y.

Here is the call graph for this function:

bool Geometry::clipLineWithQuadrangle const Line  lineToClip,
const Vector2< double > &  corner0,
const Vector2< double > &  corner1,
const Vector2< double > &  corner2,
const Vector2< double > &  corner3,
Vector2< int > &  clipPoint1,
Vector2< int > &  clipPoint2
[static]
 

Definition at line 356 of file Geometry.cpp.

References Vector2< V >::x, and Vector2< V >::y.

bool Geometry::isPointInsideRectangle const Vector2< double > &  bottomLeftCorner,
const Vector2< double > &  topRightCorner,
const Vector2< double > &  point
[static]
 

Definition at line 503 of file Geometry.cpp.

References point, Vector2< int >::x, and Vector2< int >::y.

bool Geometry::isPointInsideRectangle const Vector2< int > &  bottomLeftCorner,
const Vector2< int > &  topRightCorner,
const Vector2< int > &  point
[static]
 

Definition at line 516 of file Geometry.cpp.

References point, Vector2< int >::x, and Vector2< int >::y.

bool Geometry::clipPointInsideRectange const Vector2< int > &  bottomLeftCorner,
const Vector2< int > &  topRightCorner,
Vector2< int > &  point
[static]
 

Definition at line 528 of file Geometry.cpp.

References point, Vector2< V >::x, Vector2< int >::x, Vector2< V >::y, and Vector2< int >::y.

bool Geometry::calculatePointOnField const int  x,
const int  y,
const CameraMatrix cameraMatrix,
const CameraInfo cameraInfo,
Vector2< int > &  pointOnField
[static]
 

Calculates where a pixel in the image lies on the ground (relative to the robot).

Parameters:
x Specifies the x-coordinate of the pixel.
y Specifies the y-coordinate of the pixel.
cameraMatrix The camera matrix of the image.
cameraInfo The camera info of the image.
pointOnField The resulting point.

Definition at line 559 of file Geometry.cpp.

References Vector3< V >::x, Vector3< V >::y, and Vector3< V >::z.

Referenced by RBallSpecialist2::addBallPercept(), RasterImageProcessor::addFieldPoint(), RasterImageProcessor::addObstaclePoints(), GT2004ImageProcessor::calcEdgeAngle(), REnemySpecialist::calculateFarestPoint(), REnemySpecialist::calculateFarestPointCOG(), REnemySpecialist::calculateFarestPointFastCOG(), calculateLineSize(), REnemySpecialist::calculatePointOnFieldFromSegment(), GT2004EdgeSpecialist::checkPoint(), RFieldSpecialist::checkRamp(), GT2004ImageProcessor::clusterRobots(), GT2004EdgeSpecialist::getEdgesPercept(), and GT2004ImageProcessor::scan().

bool Geometry::calculatePointOnField const int  x,
const int  y,
const CameraMatrix cameraMatrix,
const CameraMatrix prevCameraMatrix,
const CameraInfo cameraInfo,
Vector2< int > &  pointOnField
[static]
 

Calculates where a pixel in the image lies on the ground (relative to the robot).

Parameters:
x Specifies the x-coordinate of the pixel.
y Specifies the y-coordinate of the pixel.
cameraMatrix The camera matrix of the image.
prevCameraMatrix The camera matrix of the previous image.
cameraInfo The camera info of the image.
pointOnField The resulting point.

Definition at line 596 of file Geometry.cpp.

References Vector2< V >::x, and Vector2< V >::y.

void Geometry::calculatePointInImage const Vector2< int > &  point,
const CameraMatrix cameraMatrix,
const CameraInfo cameraInfo,
Vector2< int > &  pointInImage
[static]
 

Calculates where a relative point on the ground appears in an image.

Parameters:
point The coordinates of the point relative to the robot's origin.
cameraMatrix The camera matrix of the image.
cameraInfo The camera info of the image.
pointInImage The resulting point.

Definition at line 625 of file Geometry.cpp.

References Vector2< V >::abs(), point, Vector2< V >::x, Vector2< int >::x, Vector2< V >::y, and Vector2< int >::y.

Referenced by GT2004SelfLocator::draw().

Here is the call graph for this function:

bool Geometry::getIntersectionPointsOfLineAndRectangle const Vector2< int > &  bottomLeft,
const Vector2< int > &  topRight,
const Geometry::Line  line,
Vector2< int > &  point1,
Vector2< int > &  point2
[static]
 

Clips a line with a rectangle.

Parameters:
bottomLeft The bottom left corner of the rectangle
topRight The top right corner of the rectangle
line The line to be clipped
point1 The starting point of the resulting line
point2 The end point of the resulting line
Returns:
states whether clipping was necessary (and done)

Definition at line 664 of file Geometry.cpp.

References Geometry::Line::base, Geometry::Line::direction, point, Vector2< int >::x, Vector2< V >::x, Vector2< double >::x, Vector2< int >::y, Vector2< V >::y, and Vector2< double >::y.

Referenced by BresenhamLineScan::BresenhamLineScan(), GoalRecognizer::calculateScanLinesParallelToHorizon(), GT2004GoalRecognizer::calculateScanLinesParallelToHorizon(), GT2004ImageProcessor::execute(), GT2004BeaconDetector::execute(), GT2004ImageProcessor::scanColumns(), GT2004BeaconDetector::scanForBeaconEdges(), and GT2004ImageProcessor::scanRows().

bool Geometry::clipLineWithRectangleCohenSutherland const Vector2< int > &  bottomLeft,
const Vector2< int > &  topRight,
Vector2< int > &  point1,
Vector2< int > &  point2
[static]
 

Clips a line with the Cohen-Sutherland-Algorithm.

Parameters:
bottomLeft The bottom left corner of the rectangle
topRight The top right corner of the rectangle
point1 The starting point of the line
point2 The end point of the line
Returns:
states whether clipping was necessary (and done)

Definition at line 743 of file Geometry.cpp.

References Vector2< V >::y.

Referenced by GoalRecognizer::calculateVerticalGoalScanLines(), GT2004GoalRecognizer::calculateVerticalGoalScanLines(), FieldDimensions::clipLineWithField(), FieldDimensions::clipLineWithFieldAndGoalAreas(), REdgeDetection::findStart(), CheckerboardDetector::getLineThroughPixels(), CheckerboardDetector::getMiddleAndLengthOfPerpendicular(), and RDefaultStrategy::postScan().

int Geometry::cohenSutherlandOutCode const Vector2< int > &  bottomLeft,
const Vector2< int > &  topRight,
Vector2< int > &  point
[inline, static]
 

Calculates the Cohen Sutherland Code for a given point and a given rectangle.

Definition at line 475 of file Geometry.h.

References point, Vector2< V >::x, Vector2< int >::x, Vector2< V >::y, and Vector2< int >::y.

int Geometry::intersection int  a1,
int  b1,
int  a2,
int  b2,
int  value
[static]
 

Calculates the intersection of an arbitrary line and a horizontal or vertical line.

Definition at line 815 of file Geometry.cpp.

Referenced by getIntersectionOfLines().

Vector2< double > Geometry::relative2FieldCoord RobotPose  rp,
double  x,
double  y
[static]
 

Function does the transformation from 2d relative robot coordinates to absolute field coordinates.

Parameters:
rp current Robot Pose.
x relative x-coordinate of ball (relative to robot)
y relative y-coordinate of ball (relative to robot)
Returns:
Returns the ball positon in absolute coordinates

Definition at line 825 of file Geometry.cpp.

References RotationMatrix::fromKardanRPY(), Pose2D::rotation, Pose2D::translation, Vector2< double >::x, Vector2< V >::x, Vector2< double >::y, and Vector2< V >::y.

Referenced by GT2004BallLocator::drawBallPosition(), GT2004BallLocator::execute(), GT2004BallLocator::handleSeenBall(), GT2004BallLocator::handleUnseenBall(), and KalmanConstantSpeedModel::update().

Here is the call graph for this function:

Vector2< double > Geometry::fieldCoord2Relative RobotPose  robotPose,
Vector2< double >  fieldCoord
[static]
 

Function does the transformation from 2d field coordinates to coordinates relative to the robot.

Parameters:
robotPose current Robot Pose.
fieldCoord 
Returns:
Returns the positon in relative

Definition at line 840 of file Geometry.cpp.

References angleTo(), distanceTo(), RobotPose::getPose(), Vector2< V >::x, and Vector2< V >::y.

Referenced by GT2004HeadControl::getLookAtBallAngles().

Here is the call graph for this function:

bool Geometry::calculateBallInImage const Vector2< double > &  ballOffset,
const CameraMatrix cameraMatrix,
const CameraInfo cameraInfo,
Circle circle
[static]
 

The function approximates the shape of a ball in the camera image.

Note: currently, the approximation is not exact.

Parameters:
ballOffset The ball's position relative to the robot's body origin.
cameraMatrix The position and orientation of the robot's camera.
cameraInfo The resolution and the opening angle of the robot's camera.
circle The approximated shape generated by the function.
Returns:
If false, only the center of the circle is valid, not the radius.

Definition at line 850 of file Geometry.cpp.

References Vector2< V >::abs(), calculatePointByAngles(), Geometry::Circle::center, pi_2, Geometry::Circle::radius, sqr, Pose3D::translation, Vector2< double >::x, Vector3< double >::x, Vector2< V >::x, Vector2< double >::y, Vector3< double >::y, Vector2< V >::y, and Vector3< double >::z.

Here is the call graph for this function:

double Geometry::getDistanceBySize const CameraInfo cameraInfo,
double  sizeInReality,
double  sizeInPixels
[static]
 

Definition at line 891 of file Geometry.cpp.

Referenced by RBridgeSpecialist::findBridgeMark(), BallPercept::getOffsetIntrinsic(), GoalRecognizer::scanLinesForGoals(), and GT2004GoalRecognizer::scanLinesForGoals().

double Geometry::getDistanceBySize const CameraInfo cameraInfo,
double  sizeInReality,
double  sizeInPixels,
int  centerX,
int  centerY
[static]
 

The function determines how far an object is away depending on its real size and the size in the image along with its center position, using camera intrinsic parameters.

Parameters:
cameraInfo Class containing the intrinsic paramaters
sizeInReality The real size of the object.
sizeInPixels The size in the image.
centerX X coordinate (in image reference) of object's baricenter.
centerY Y coordinate (in image reference) of object's baricenter.
Returns:
The distance between camera and object.

Definition at line 902 of file Geometry.cpp.

double Geometry::getDistanceByAngleSize double  sizeInReality,
double  sizeInPixels
[static]
 

The function determines how far an object is away depending on its real size and the size in the image.

Parameters:
sizeInReality The real size of the object.
sizeInPixels The size in the image.
Returns:
The distance between camera and object.

Definition at line 921 of file Geometry.cpp.

double Geometry::getBallDistanceByAngleSize double  sizeInReality,
double  sizeInPixels
[static]
 

The function determines how far the ball is away depending on its real size and the size in the image.

Parameters:
sizeInReality The real size of the ball.
sizeInPixels The size in the image.
Returns:
The distance between the camera and the ball.

Definition at line 930 of file Geometry.cpp.

Referenced by BallPercept::getOffsetSizeBased().

double Geometry::getSizeByDistance double  sizeInReality,
double  distance,
double  imageWidthPixels,
double  imageWidthAngle
[static]
 

The function determines how big an object appears in the image depending on its distance and size.

Parameters:
sizeInReality The real size of the object.
distance The distance to the object.
imageWidthPixels The horizontal resolution of the image.
imageWidthAngle The horizontal opening angle of the camera.
Returns:
The size as it would appear in the image.

Definition at line 951 of file Geometry.cpp.

Referenced by calculateLineSize(), and GT2004ImageProcessor::scan().

double Geometry::getSizeByDistance const CameraInfo cameraInfo,
double  sizeInReality,
double  distance
[static]
 

The function determines how big an object appears in the image depending on its distance and size.

Parameters:
cameraInfo Object containing camera paramters.
sizeInReality The real size of the object.
distance The distance to the object.
Returns:
The size as it would appear in the image.

Definition at line 939 of file Geometry.cpp.

Geometry::Line Geometry::calculateHorizon const CameraMatrix cameraMatrix,
const CameraInfo cameraInfo
[static]
 

The function calculates the horizon.

Parameters:
cameraMatrix The camera matrix.
cameraInfo Object containing camera parameters.
Returns:
The line of the horizon in the image.

Definition at line 964 of file Geometry.cpp.

References Geometry::Line::base, Geometry::Line::direction, Geometry::Line::normalizeDirection(), Vector2< double >::x, and Vector2< double >::y.

Referenced by GT2004ImageProcessor::execute(), GT2004GoalRecognizer::execute(), GoalRecognizer::getGoalPercept(), and RasterImageProcessor::init().

Here is the call graph for this function:

int Geometry::calculateLineSize const Vector2< int > &  pointInImage,
const CameraMatrix cameraMatrix,
const CameraInfo cameraInfo
[static]
 

The function calculates the expected size (pixel) of a field line in an image.

Parameters:
pointInImage The point where the line is expected.
cameraMatrix The camera matrix.
cameraInfo Object containing the camera parameters.
Returns:
The size of a line pixel.

Definition at line 1006 of file Geometry.cpp.

References Vector2< V >::abs(), calculatePointOnField(), getSizeByDistance(), and sqr.

Referenced by GT2004EdgeSpecialist::getEdgesPercept(), and GT2004ImageProcessor::scan().

Here is the call graph for this function:

double Geometry::pixelSizeToAngleSize double  pixelSize,
const CameraInfo cameraInfo
[static]
 

Calculates the angle size for a given pixel size.

Definition at line 885 of file Geometry.cpp.

References CameraInfo::focalLengthInv.

double Geometry::angleSizeToPixelSize double  angleSize,
const CameraInfo cameraInfo
[static]
 

Calculates the pixel size for a given angle size.

Definition at line 880 of file Geometry.cpp.

References CameraInfo::focalLength.

void Geometry::radialDistortionCorrection const CameraInfo cameraInfo,
const int  srcX,
const int  srcY,
double &  correctedX,
double &  correctedY
[inline, static]
 

Corrects the radial distortion introduced by the camera lens (using a 4th order model) of a given pixel.

Parameters:
cameraInfo Class containing camera intrinsic parameters
srcX X coordinate (image reference) of pixel to be distortion-corrected.
srcY Y coordinate (image reference) of pixel to be distortion-corrected.
correctedX X coordinate (image reference) of resulting distortion-corrected pixel.
correctedY Y coordinate (image reference) of resulting distortion-corrected pixel.

Definition at line 661 of file Geometry.h.

References CameraInfo::focalLenPow2, CameraInfo::focalLenPow4, CameraInfo::fourthOrderRadialDistortion, CameraInfo::opticalCenter, CameraInfo::secondOrderRadialDistortion, Vector2< double >::x, and Vector2< double >::y.

Referenced by setupRadialCorrection().

void Geometry::setupRadialCorrection const CameraInfo cameraInfo  )  [static]
 

This function builds a radial distortion correction look-up table based on the parameters contained in cameraInfo.

Parameters:
cameraInfo Object containing intrinisc (and other) camera parameters.

Definition at line 1026 of file Geometry.cpp.

References radialCorrectionLUT, radialDistortionCorrection(), CameraInfo::resolutionHeight, CameraInfo::resolutionWidth, Geometry::CorrectedCoords::x, and Geometry::CorrectedCoords::y.

Referenced by setupRadialCorrectionERS210(), and setupRadialCorrectionERS7().

Here is the call graph for this function:

void Geometry::setupRadialCorrectionERS7  )  [inline, static]
 

Definition at line 679 of file Geometry.h.

References setupRadialCorrection().

Here is the call graph for this function:

void Geometry::setupRadialCorrectionERS210  )  [inline, static]
 

Definition at line 685 of file Geometry.h.

References setupRadialCorrection().

Here is the call graph for this function:

bool Geometry::insideCircle Geometry::Circle circle,
double  radius2,
double  x,
double  y
[inline, static]
 

Definition at line 691 of file Geometry.h.

References Geometry::Circle::center, Vector2< double >::x, and Vector2< double >::y.

Referenced by RBallSpecialist2::validateCircle().

void Geometry::radialDistortionCorrectionFast const int  srcX,
const int  srcY,
int &  correctedX,
int &  correctedY
[inline, static]
 

Corrects the radial distortion introduced by the camera lens (using a 4th order model) of a given pixel, using a pre-computed look-up table.

Parameters:
srcX X coordinate (image reference) of pixel to be distortion-corrected.
srcY Y coordinate (image reference) of pixel to be distortion-corrected.
correctedX X coordinate (image reference) of resulting distortion-corrected pixel.
correctedY Y coordinate (image reference) of resulting distortion-corrected pixel.

Definition at line 704 of file Geometry.h.

References radialCorrectionLUT, Geometry::CorrectedCoords::x, and Geometry::CorrectedCoords::y.


Member Data Documentation

Geometry::CorrectedCoords Geometry::radialCorrectionLUT [static, private]
 

Definition at line 1024 of file Geometry.cpp.

Referenced by radialDistortionCorrectionFast(), and setupRadialCorrection().


The documentation for this class was generated from the following files:
Generated on Thu Sep 23 20:06:30 2004 for GT2004 by doxygen 1.3.6