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

GT2004BallSpecialist Class Reference

The BallSpecialist finds a single ball in an image. More...

#include <GT2004BallSpecialist.h>

Collaboration diagram for GT2004BallSpecialist:

Collaboration graph
[legend]
List of all members.

Public Member Functions

 GT2004BallSpecialist (const ColorCorrector &colorCorrector)
void searchBall (const Image &image, const ColorTable &colorTable, const CameraMatrix &cameraMatrix, const CameraMatrix &prevCameraMatrix, int x, int y, BallPercept &ballPercept)
 Searches for the ball in the image, starting from the secified point.

unsigned char getSimilarityToOrange (unsigned char y, unsigned char u, unsigned char v)
 Returns the Similarity of the given color to orange.


Private Member Functions

void scanForBallPoints (const Image &image, const CameraInfo &bwCameraInfo, const ColorTable &colorTable, int x, int y, BallPointList &ballPoints, int &countAmbiguous, int &countOrange, int &maxOrangePerLine, int &countPixel)
 Scan for the ball starting at a given trigger point.

bool findEndOfBall (const Image &image, const CameraInfo &bwCameraInfo, const ColorTable &colorTable, const BallPoint &start, const Vector2< int > &step, BallPoint &destination, int &countAmbiguous, int &countOrange, int &maxOrangePerLine, int &countPixel)
 Finds the end of the ball.

bool createBallPerceptLevenbergMarquardt (const BallPointList &ballPoints, Vector2< int > &center, double &radius)
 The function tries to calculate the ball percept by using the Levenberg-Marquardt algorithm.

bool checkIfPointsAreInsideBall (const BallPointList &ballPoints, Vector2< int > &center, double radius)
void addBallPercept (const Image &image, const CameraInfo &bwCameraInfo, const ColorTable &colorTable, const CameraMatrix &cameraMatrix, const CameraMatrix &prevCameraMatrix, const Vector2< int > &center, double radius, BallPercept &ballPercept)
 The function checks whether a ball percept is plausible and will add it if so.


Private Attributes

const ColorCorrectorcolorCorrector

Detailed Description

The BallSpecialist finds a single ball in an image.

Definition at line 28 of file GT2004BallSpecialist.h.


Constructor & Destructor Documentation

GT2004BallSpecialist::GT2004BallSpecialist const ColorCorrector colorCorrector  ) 
 

Definition at line 24 of file GT2004BallSpecialist.cpp.


Member Function Documentation

void GT2004BallSpecialist::searchBall const Image image,
const ColorTable colorTable,
const CameraMatrix cameraMatrix,
const CameraMatrix prevCameraMatrix,
int  x,
int  y,
BallPercept ballPercept
 

Searches for the ball in the image, starting from the secified point.

Definition at line 33 of file GT2004BallSpecialist.cpp.

References GT2004BallSpecialist::BallPointList::add(), DEBUG_DRAWING_FINISHED, CameraInfo::focalLength, CameraInfo::focalLengthInv, GT2004BallSpecialist::BallPointList::number, CameraInfo::opticalCenter, CameraInfo::resolutionHeight, CameraInfo::resolutionWidth, Vector2< double >::x, and Vector2< double >::y.

Referenced by GT2004ImageProcessor::execute().

Here is the call graph for this function:

unsigned char GT2004BallSpecialist::getSimilarityToOrange unsigned char  y,
unsigned char  u,
unsigned char  v
[inline]
 

Returns the Similarity of the given color to orange.

Definition at line 49 of file GT2004BallSpecialist.h.

References Image::convertFromYCbCrToRGB(), max, and min.

Referenced by findEndOfBall().

Here is the call graph for this function:

void GT2004BallSpecialist::scanForBallPoints const Image image,
const CameraInfo bwCameraInfo,
const ColorTable colorTable,
int  x,
int  y,
BallPointList ballPoints,
int &  countAmbiguous,
int &  countOrange,
int &  maxOrangePerLine,
int &  countPixel
[private]
 

Scan for the ball starting at a given trigger point.

Definition at line 158 of file GT2004BallSpecialist.cpp.

References GT2004BallSpecialist::BallPoint::atBorder, DOT, findEndOfBall(), Vector2< V >::x, Vector2< int >::x, Vector2< V >::y, and Vector2< int >::y.

Here is the call graph for this function:

bool GT2004BallSpecialist::findEndOfBall const Image image,
const CameraInfo bwCameraInfo,
const ColorTable colorTable,
const BallPoint start,
const Vector2< int > &  step,
BallPoint destination,
int &  countAmbiguous,
int &  countOrange,
int &  maxOrangePerLine,
int &  countPixel
[private]
 

Finds the end of the ball.

Definition at line 352 of file GT2004BallSpecialist.cpp.

References colorClass, colorCorrector, ColorCorrector::correct(), CORRECTED_COLOR_CLASS, getSimilarityToOrange(), LINE, and max.

Referenced by scanForBallPoints().

Here is the call graph for this function:

bool GT2004BallSpecialist::createBallPerceptLevenbergMarquardt const BallPointList ballPoints,
Vector2< int > &  center,
double &  radius
[private]
 

The function tries to calculate the ball percept by using the Levenberg-Marquardt algorithm.

The function fails if less than 3 points are available.

Returns:
true if ball percept was created

Definition at line 526 of file GT2004BallSpecialist.cpp.

References idText, OUTPUT, and Matrix_nxn< T, N >::solve().

Here is the call graph for this function:

bool GT2004BallSpecialist::checkIfPointsAreInsideBall const BallPointList ballPoints,
Vector2< int > &  center,
double  radius
[private]
 

Definition at line 605 of file GT2004BallSpecialist.cpp.

References Geometry::distance(), and GT2004BallSpecialist::BallPointList::number.

Here is the call graph for this function:

void GT2004BallSpecialist::addBallPercept const Image image,
const CameraInfo bwCameraInfo,
const ColorTable colorTable,
const CameraMatrix cameraMatrix,
const CameraMatrix prevCameraMatrix,
const Vector2< int > &  center,
double  radius,
BallPercept ballPercept
[private]
 

The function checks whether a ball percept is plausible and will add it if so.

Parameters:
image The image the ballpercept comes from.
bwCameraInfo Object containing camera parameters.
colorTable The colortable to be used
cameraMatrix The matrix of the camera of the image.
prevCameraMatrix The matrix of the camera of a previous image.
center The center of the ball.
radius The radius of the ball.
ballPercept The object the ball is added to.

Definition at line 618 of file GT2004BallSpecialist.cpp.

References Geometry::calculateAnglesForPoint(), colorClass, CORRECTED_COLOR_CLASS, DOT, BresenhamLineScan::getNext(), BresenhamLineScan::init(), BresenhamLineScan::numberOfPixels, pi_4, Vector2< V >::x, Vector2< V >::y, and Vector3< V >::z.

Here is the call graph for this function:


Member Data Documentation

const ColorCorrector& GT2004BallSpecialist::colorCorrector [private]
 

Definition at line 169 of file GT2004BallSpecialist.h.

Referenced by findEndOfBall().


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