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

GT2005BallSpecialist Class Reference

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

#include <GT2005BallSpecialist.h>

Collaboration diagram for GT2005BallSpecialist:

Collaboration graph
[legend]
List of all members.

Public Member Functions

 GT2005BallSpecialist (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.

void resetMultiplePerceptsList (BallPercept &ballPercept)
void forwardPercept (BallPercept &ballPercept)

Public Attributes

List< MultipleBallPerceptElementmultiplePercepts

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 calculateDeviationOfBallPoints (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.

void considerBallPoints (const BallPointList &ballPoints)
 The function calculates the factor durabilityOfBallPoints that will be needed later to calculate a reliability for the percept.

double calculateReliability (double percentOfOrange, double radius, Vector2< double > anglesToCenter, const CameraInfo bwCameraInfo, const CameraMatrix &cameraMatrix, const CameraMatrix &prevCameraMatrix)
 The function calculates the reliability of the ball percept.

void addMultiplePercept (const MultipleBallPerceptElement &newPercept)

Private Attributes

const ColorCorrectorcolorCorrector
double deviationOfBallPoints
double durabilityOfBallPoints

Detailed Description

The BallSpecialist finds a single ball in an image.

Definition at line 32 of file GT2005BallSpecialist.h.


Constructor & Destructor Documentation

GT2005BallSpecialist::GT2005BallSpecialist const ColorCorrector colorCorrector  ) 
 

Definition at line 25 of file GT2005BallSpecialist.cpp.


Member Function Documentation

void GT2005BallSpecialist::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 35 of file GT2005BallSpecialist.cpp.

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

Referenced by SlamImageProcessor::execute(), and GT2005ImageProcessor::execute().

Here is the call graph for this function:

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

Returns the Similarity of the given color to orange.

Definition at line 53 of file GT2005BallSpecialist.h.

References ColorModelConversions::fromYCbCrToRGB(), max, and min.

Referenced by findEndOfBall().

Here is the call graph for this function:

void GT2005BallSpecialist::resetMultiplePerceptsList BallPercept ballPercept  ) 
 

Definition at line 907 of file GT2005BallSpecialist.cpp.

References List< MultipleBallPerceptElement >::clear(), BallPercept::multiplePercepts, and MultipleBallPerceptList::numberOfElements.

Referenced by SlamImageProcessor::execute(), and GT2005ImageProcessor::execute().

Here is the call graph for this function:

void GT2005BallSpecialist::forwardPercept BallPercept ballPercept  ) 
 

Definition at line 937 of file GT2005BallSpecialist.cpp.

References MultipleBallPerceptList::add(), List< MultipleBallPerceptElement >::getFirst(), List< MultipleBallPerceptElement >::getSize(), and BallPercept::multiplePercepts.

Referenced by SlamImageProcessor::execute().

Here is the call graph for this function:

void GT2005BallSpecialist::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 166 of file GT2005BallSpecialist.cpp.

References GT2005BallSpecialist::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 GT2005BallSpecialist::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 360 of file GT2005BallSpecialist.cpp.

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

Referenced by scanForBallPoints().

Here is the call graph for this function:

bool GT2005BallSpecialist::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 554 of file GT2005BallSpecialist.cpp.

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

Here is the call graph for this function:

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

Definition at line 633 of file GT2005BallSpecialist.cpp.

References deviationOfBallPoints, Geometry::distance(), and GT2005BallSpecialist::BallPointList::number.

Here is the call graph for this function:

void GT2005BallSpecialist::calculateDeviationOfBallPoints const BallPointList ballPoints,
Vector2< int > &  center,
double  radius
[private]
 

Definition at line 663 of file GT2005BallSpecialist.cpp.

References deviationOfBallPoints, Geometry::distance(), and GT2005BallSpecialist::BallPointList::number.

Here is the call graph for this function:

void GT2005BallSpecialist::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 784 of file GT2005BallSpecialist.cpp.

References BallPercept::addHighRes(), Geometry::calculateAnglesForPoint(), MultipleBallPerceptElement::calculateDistanceValue(), BallPercept::centerInImage, CIRCLE, Geometry::clipPointInsideRectange(), CORRECTED_COLOR_CLASS, DOT, BresenhamLineScan::getNext(), BresenhamLineScan::init(), BresenhamLineScan::numberOfPixels, BallPercept::offsetOnField, MultipleBallPerceptElement::offsetOnField, pi_4, Geometry::pixelSizeToAngleSize(), BallPercept::radiusInImage, BallPercept::reliability, MultipleBallPerceptElement::reliability, Vector2< double >::x, Vector2< V >::x, Vector2< double >::y, Vector2< V >::y, and Vector3< V >::z.

Here is the call graph for this function:

void GT2005BallSpecialist::considerBallPoints const BallPointList ballPoints  )  [private]
 

The function calculates the factor durabilityOfBallPoints that will be needed later to calculate a reliability for the percept.

Definition at line 687 of file GT2005BallSpecialist.cpp.

References durabilityOfBallPoints, and GT2005BallSpecialist::BallPointList::number.

double GT2005BallSpecialist::calculateReliability double  percentOfOrange,
double  radius,
Vector2< double >  anglesToCenter,
const CameraInfo  bwCameraInfo,
const CameraMatrix cameraMatrix,
const CameraMatrix prevCameraMatrix
[private]
 

The function calculates the reliability of the ball percept.

Definition at line 739 of file GT2005BallSpecialist.cpp.

References deviationOfBallPoints, durabilityOfBallPoints, Geometry::getBallDistanceByAngleSize(), max, Pose3D::translation, Vector2< V >::y, and Vector3< double >::z.

Here is the call graph for this function:

void GT2005BallSpecialist::addMultiplePercept const MultipleBallPerceptElement newPercept  )  [private]
 

Definition at line 914 of file GT2005BallSpecialist.cpp.

References List< MultipleBallPerceptElement >::getFirst(), List< MultipleBallPerceptElement >::getSize(), List< MultipleBallPerceptElement >::insert(), and MultipleBallPerceptElement::reliability.

Here is the call graph for this function:


Member Data Documentation

List<MultipleBallPerceptElement> GT2005BallSpecialist::multiplePercepts
 

Definition at line 70 of file GT2005BallSpecialist.h.

const ColorCorrector& GT2005BallSpecialist::colorCorrector [private]
 

Definition at line 195 of file GT2005BallSpecialist.h.

Referenced by findEndOfBall().

double GT2005BallSpecialist::deviationOfBallPoints [private]
 

Definition at line 198 of file GT2005BallSpecialist.h.

Referenced by calculateDeviationOfBallPoints(), calculateReliability(), and checkIfPointsAreInsideBall().

double GT2005BallSpecialist::durabilityOfBallPoints [private]
 

Definition at line 199 of file GT2005BallSpecialist.h.

Referenced by calculateReliability(), and considerBallPoints().


The documentation for this class was generated from the following files:
Generated on Mon Mar 20 22:13:00 2006 for GT2005 by doxygen 1.3.6