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

Vector2< V > Class Template Reference

This class represents a 2-vector. More...

#include <Vector2.h>

Collaboration diagram for Vector2< V >:

Collaboration graph
[legend]
List of all members.

Public Member Functions

 Vector2 ()
 Default constructor.

 Vector2 (V x, V y)
 Default constructor.

Vector2< V > & operator= (const Vector2< V > &other)
 Assignment operator.

 Vector2 (const Vector2< V > &other)
 Copy constructor.

Vector2< V > & operator+= (const Vector2< V > &other)
 Addition of another vector to this one.

Vector2< V > & operator-= (const Vector2< V > &other)
 Substraction of this vector from another one.

Vector2< V > & operator *= (const V &factor)
 Multiplication of this vector by a factor.

Vector2< V > & operator/= (const V &factor)
 Division of this vector by a factor.

Vector2< V > operator+ (const Vector2< V > &other) const
 Addition of another vector to this one.

Vector2< V > operator- (const Vector2< V > &other) const
 Subtraction of another vector to this one.

Vector2< V > operator- () const
 Negation of this vector.

operator * (const Vector2< V > &other) const
 Inner product of this vector and another one.

Vector2< V > operator * (const V &factor) const
 Multiplication of this vector by a factor.

Vector2< V > operator/ (const V &factor) const
 Division of this vector by a factor.

bool operator== (const Vector2< V > &other) const
 Comparison of another vector with this one.

bool operator!= (const Vector2< V > &other) const
 Comparison of another vector with this one.

abs () const
 Calculation of the length of this vector.

Vector2< V > normalize (V len)
 normalize this vector.

Vector2< V > normalize ()
 normalize this vector.

Vector2< V > transpose ()
 transpose this vector.

Vector2< V > rotateLeft ()
 the vector is rotated left by 90 degrees.

Vector2< V > rotateRight ()
 the vector is rotated right by 90 degrees.

V & operator[] (int i)
 array-like member access.

double angle () const
 Calculation of the angle of this vector.


Public Attributes

x
 The vector values.

y
 The vector values.


Detailed Description

template<class V>
class Vector2< V >

This class represents a 2-vector.

Definition at line 16 of file Vector2.h.


Constructor & Destructor Documentation

template<class V>
Vector2< V >::Vector2  )  [inline]
 

Default constructor.

template<class V>
Vector2< V >::Vector2 x,
y
[inline]
 

Default constructor.

template<class V>
Vector2< V >::Vector2 const Vector2< V > &  other  )  [inline]
 

Copy constructor.

Parameters:
other The other vector that is copied to this one


Member Function Documentation

template<class V>
Vector2<V>& Vector2< V >::operator= const Vector2< V > &  other  )  [inline]
 

Assignment operator.

Parameters:
other The other vector that is assigned to this one
Returns:
A reference to this object after the assignment.

Reimplemented in SeenBallPosition, and GT2004BallSpecialist::BallPoint.

Definition at line 34 of file Vector2.h.

template<class V>
Vector2<V>& Vector2< V >::operator+= const Vector2< V > &  other  )  [inline]
 

Addition of another vector to this one.

Parameters:
other The other vector that will be added to this one
Returns:
A reference to this object after the calculation.

Definition at line 49 of file Vector2.h.

template<class V>
Vector2<V>& Vector2< V >::operator-= const Vector2< V > &  other  )  [inline]
 

Substraction of this vector from another one.

Parameters:
other The other vector this one will be substracted from
Returns:
A reference to this object after the calculation.

Definition at line 60 of file Vector2.h.

template<class V>
Vector2<V>& Vector2< V >::operator *= const V &  factor  )  [inline]
 

Multiplication of this vector by a factor.

Parameters:
factor The factor this vector is multiplied by
Returns:
A reference to this object after the calculation.

Definition at line 71 of file Vector2.h.

template<class V>
Vector2<V>& Vector2< V >::operator/= const V &  factor  )  [inline]
 

Division of this vector by a factor.

Parameters:
factor The factor this vector is divided by
Returns:
A reference to this object after the calculation.

Definition at line 82 of file Vector2.h.

template<class V>
Vector2<V> Vector2< V >::operator+ const Vector2< V > &  other  )  const [inline]
 

Addition of another vector to this one.

Parameters:
other The other vector that will be added to this one
Returns:
A new object that contains the result of the calculation.

Definition at line 94 of file Vector2.h.

template<class V>
Vector2<V> Vector2< V >::operator- const Vector2< V > &  other  )  const [inline]
 

Subtraction of another vector to this one.

Parameters:
other The other vector that will be added to this one
Returns:
A new object that contains the result of the calculation.

Definition at line 101 of file Vector2.h.

template<class V>
Vector2<V> Vector2< V >::operator-  )  const [inline]
 

Negation of this vector.

Returns:
A new object that contains the result of the calculation.

Definition at line 107 of file Vector2.h.

template<class V>
V Vector2< V >::operator * const Vector2< V > &  other  )  const [inline]
 

Inner product of this vector and another one.

Parameters:
other The other vector this one will be multiplied by
Returns:
The inner product.

Definition at line 114 of file Vector2.h.

template<class V>
Vector2<V> Vector2< V >::operator * const V &  factor  )  const [inline]
 

Multiplication of this vector by a factor.

Parameters:
factor The factor this vector is multiplied by
Returns:
A new object that contains the result of the calculation.

Definition at line 123 of file Vector2.h.

template<class V>
Vector2<V> Vector2< V >::operator/ const V &  factor  )  const [inline]
 

Division of this vector by a factor.

Parameters:
factor The factor this vector is divided by
Returns:
A new object that contains the result of the calculation.

Definition at line 131 of file Vector2.h.

template<class V>
bool Vector2< V >::operator== const Vector2< V > &  other  )  const [inline]
 

Comparison of another vector with this one.

Parameters:
other The other vector that will be compared to this one
Returns:
Whether the two vectors are equal.

Definition at line 138 of file Vector2.h.

template<class V>
bool Vector2< V >::operator!= const Vector2< V > &  other  )  const [inline]
 

Comparison of another vector with this one.

Parameters:
other The other vector that will be compared to this one.
Returns:
Whether the two vectors are unequal.

Definition at line 147 of file Vector2.h.

template<class V>
V Vector2< V >::abs  )  const [inline]
 

Calculation of the length of this vector.

Returns:
The length.

Definition at line 153 of file Vector2.h.

Referenced by GT2004EdgeSpecialist::addCandidate(), Field::addCoords(), GT2004ImageProcessor::calcEdgeAngle(), Geometry::calculateBallInImage(), GT2004HeadControl::calculateClosestLandmark(), Geometry::calculateLineSize(), Geometry::calculatePointInImage(), Field::clip(), GT2004ImageProcessor::clusterRobots(), GT2004PotentialFieldBasicBehaviorOffensiveSupport::execute(), GT2004PotentialFieldBasicBehaviorSupport::execute(), GT2004PotentialFieldBasicBehaviorGoToPose::execute(), RBridgeSpecialist::findBridgeMark(), GT2004SelfLocator::generatePoseTemplates(), Kinematics::getAbsoluteRobotVertices(), Field::getClosestPoint(), BallPercept::getDistance(), BallPercept::getDistanceBearingBased(), BallPercept::getDistanceIntrinsicBased(), BallPercept::getDistanceSizeBased(), GT2004HeadControl::getLookAtBallAngles(), Vector2< int >::normalize(), GT2004SelfLocator::poseFromBearings(), GT2004SelfLocator::poseFromBearingsAndDistance(), GT2004ImageProcessor::scan(), GT2004BeaconDetector::scanForBeaconEdges(), BoxSpecialist::searchGoal(), BoxSpecialist::searchLandmark(), GT2004HeadControl::setJoints(), and GT2004SelfLocator::updateByPoint().

template<class V>
Vector2<V> Vector2< V >::normalize len  )  [inline]
 

normalize this vector.

Parameters:
len The length, the vector should be normalized to, default=1.
Returns:
the normalized vector.

Definition at line 160 of file Vector2.h.

Referenced by GT2004EdgeSpecialist::addCandidate(), GT2004ImageProcessor::execute(), GT2004BasicBehaviorGoToBallWithoutTurning::execute(), GT2004BasicBehaviorGoToBall::execute(), Geometry::getDistanceToLine(), RasterSpecialist::getDistanceToLine(), GT2004BallLocator::handleSeenBall(), GT2004HeadControl::setJoints(), OpenChallengeSymbols::update(), FieldDimensions::vectorToBorder(), and FieldDimensions::vectorToBorderIncludingGoals().

template<class V>
Vector2<V> Vector2< V >::normalize  )  [inline]
 

normalize this vector.

Returns:
the normalized vector.

Definition at line 169 of file Vector2.h.

template<class V>
Vector2<V> Vector2< V >::transpose  )  [inline]
 

transpose this vector.

Returns:
the transposed vector.

Definition at line 178 of file Vector2.h.

template<class V>
Vector2<V> Vector2< V >::rotateLeft  )  [inline]
 

the vector is rotated left by 90 degrees.

Returns:
the rotated vector.

Definition at line 188 of file Vector2.h.

Referenced by RDefaultStrategy::preScan(), and OpenChallengeSymbols::update().

template<class V>
Vector2<V> Vector2< V >::rotateRight  )  [inline]
 

the vector is rotated right by 90 degrees.

Returns:
the rotated vector.

Definition at line 198 of file Vector2.h.

Referenced by OpenChallengeSymbols::update().

template<class V>
V& Vector2< V >::operator[] int  i  )  [inline]
 

array-like member access.

Parameters:
i index of coordinate
Returns:
reference to x or y

Definition at line 210 of file Vector2.h.

template<class V>
double Vector2< V >::angle  )  const [inline]
 

Calculation of the angle of this vector.

Definition at line 216 of file Vector2.h.

Referenced by GT2004ObstaclesLocator::addPSDPercept(), GT2004ImageProcessor::calcEdgeAngle(), GT2004HeadControl::calculateClosestLandmark(), ChallengeSpecialVision::executeReset(), Kinematics::getAbsoluteRobotVertices(), BallPercept::getAngle(), BallPercept::getAngleBearingBased(), BallPercept::getAngleIntrinsicBased(), BallPercept::getAngleSizeBased(), Kinematics::getRobotTransformation(), GT2004ImageProcessor::scan(), and OpenChallengeSymbols::update().


Member Data Documentation

template<class V>
V Vector2< V >::x
 

The vector values.

Definition at line 19 of file Vector2.h.

Referenced by KalmanFixedPositionModel::adapt(), KalmanConstantSpeedModel::adapt(), Boundary< double >::add(), RBallSpecialist2::addBallPercept(), GT2004BallSpecialist::addBallPercept(), Field::addCoords(), LandmarksPercept::addFlag(), RasterImageProcessor::addFlag(), LandmarksPercept::addGoal(), RasterImageProcessor::addObstaclePoints(), GT2004PlayersLocator::addOppPlayerPercepts(), GT2004PlayersLocator::addOwnPlayerPercepts(), Field::addPlayer(), GT2004ObstaclesLocator::addPSDPercept(), RFieldSpecialist::analyzeLines(), AngleRelativeToHorizontal(), GT2004HeadControl::beginBallSearchAt(), GT2004ImageProcessor::calcEdgeAngle(), Geometry::calculateBallInImage(), REnemySpecialist::calculateFarestPoint(), REnemySpecialist::calculateFarestPointCOG(), REnemySpecialist::calculateFarestPointFastCOG(), RBallSpecialist2::calculateLargeCircle(), Geometry::calculatePointInImage(), Geometry::calculatePointOnField(), GoalRecognizer::calculateVerticalGoalScanLines(), GT2004GoalRecognizer::calculateVerticalGoalScanLines(), RasterStrategy::checkColor(), RasterSpecialist::checkColor(), BallPercept::checkOffset(), RFieldSpecialist::checkRamp(), Field::clip(), FieldDimensions::clipLineWithField(), FieldDimensions::clipLineWithFieldAndGoalAreas(), Geometry::clipLineWithQuadrangle(), Geometry::clipPointInsideRectange(), GT2004BeaconDetector::clusterPinkBeaconParts(), GT2004ImageProcessor::clusterRobots(), Geometry::cohenSutherlandOutCode(), GT2004BallLocator::compensateOdometry(), ObservationTable< 280, 200, 25 >::create(), RBridgeSpecialist::createBBox(), BoxSpecialist::createBBox(), CircleCalculation::createCircle(), CircleCalculation::cutMiddlePerpendiculars(), BoxSpecialist::detectFreePartOfGoal(), FieldDimensions::distanceToBorder(), FieldDimensions::distanceToOpponentPenaltyArea(), Field::draw(), ObservationTable< 280, 200, 25 >::draw(), GT2004SelfLocator::draw(), GT2004BallLocator::drawBallPosition(), RFieldSpecialist::drawCircle(), RFieldSpecialist::drawCross(), RFieldSpecialist::drawLine(), MotionRecognition::drawPixelFlow(), edge::edge(), BB2004Calibrator::evolve(), GT2004ImageProcessor::execute(), GT2004BeaconDetector::execute(), CheckerboardDetector::execute(), GT2004BasicBehaviorTurnAroundPoint::execute(), GT2004BasicBehaviorGoaliePosition::execute(), GT2004BasicBehaviorGoToBallWithoutTurning::execute(), GT2004BasicBehaviorGoToBall::execute(), GT2004PotentialFieldBasicBehaviorGoToPose::execute(), REnemySpecialist::executePostProcessing(), ChallengeSpecialVision::executeReset(), Geometry::fieldCoord2Relative(), RBridgeSpecialist::findBridgeMark(), GT2004FlagSpecialist::findEndOfFlag(), REdgeDetection::findStart(), BoxSpecialist::fitLandmark(), GT2004SelfLocator::generatePoseTemplates(), CheckerboardDetector::getAngleBetweenScreenPoints(), MotionRecognition::getAngleYZ(), MotionRecognition::getCenteredCoor(), Field::getClosestPoint(), RasterStrategy::getColor(), RasterSpecialist::getColor(), MotionRecognition::getCoorInmm(), MotionRecognition::getCoorInPixel(), extLinePair::getDirection(), Field::getDistance(), Geometry::getDistanceToLine(), RasterSpecialist::getDistanceToLine(), Field::getDistanceToOwnPenaltyArea(), GT2004EdgeSpecialist::getEdgesPercept(), CheckerboardDetector::getExactTransitionMiddle(), GT2004FlagSpecialist::getFlagPercept(), Geometry::getIntersectionOfLines(), Geometry::getIntersectionPointsOfLineAndRectangle(), GT2004HeadControl::getLookAtBallAngles(), CheckerboardDetector::getMiddleAndLengthOfPerpendicular(), BallPercept::getOffsetBearingBased(), BallPercept::getOffsetIntrinsic(), BallPercept::getOffsetSizeBased(), MotionRecognition::getPixelDiff(), MotionRecognition::getPixelFlow(), RBridgeSpecialist::getPosition(), CheckerboardDetector::getPositionFromAngles(), MotionRecognition::getRobotTranslationFromOdometry(), GT2004BallLocator::handleSeenBall(), GT2004BallLocator::handleUnseenBall(), horLinePair::horLinePair(), RFieldSpecialist::invokeOnPreScan(), MotionRecognition::isDiff(), Boundary< double >::isInside(), FieldDimensions::isInsideField(), FieldDimensions::isInsideGoal(), FieldDimensions::isInsideOpponentGoal(), FieldDimensions::isInsideOwnGoal(), FieldDimensions::isOnOpponentGoalGroundline(), FieldDimensions::isOnOwnGoalGroundline(), RasterImageProcessor::isValidPoint(), Geometry::Line::Line(), LinesPercept::LinePoint::LinePoint(), makeLine(), mil(), Vector2< int >::operator *(), Matrix2x2< double >::operator *(), Vector2< int >::operator+=(), Vector2< int >::operator-=(), LinePair2::operator<(), Vector2< int >::operator=(), LinesPercept::LinePoint::operator=(), SeenBallPosition::operator=(), GT2004BallSpecialist::BallPoint::operator=(), Vector2< int >::operator==(), operator>>(), MotionRecognition::pixelInImage(), GT2004ImageProcessor::plot(), GT2004SelfLocator::poseFromBearings(), GT2004SelfLocator::poseFromBearingsAndDistance(), RDefaultStrategy::postScan(), RDefaultStrategy::preScan(), TeamMessage::read(), Geometry::relative2FieldCoord(), RasterSpecialist::scan(), GT2004ImageProcessor::scan(), GT2004ImageProcessor::scanColumns(), RasterSpecialist::scanEast(), GT2004BallSpecialist::scanForBallPoints(), GT2004BeaconDetector::scanForBeaconEdges(), GT2004BeaconDetector::scanForBeaconPart(), GT2004BeaconDetector::scanForPink(), GoalRecognizer::scanHorizontalForGoals(), GT2004GoalRecognizer::scanHorizontalForGoals(), GoalRecognizer::scanLinesForGoals(), GT2004GoalRecognizer::scanLinesForGoals(), RasterSpecialist::scanNE(), RasterSpecialist::scanNorth(), RasterSpecialist::scanNW(), GT2004ImageProcessor::scanRows(), RasterSpecialist::scanSE(), RasterSpecialist::scanSouth(), RasterSpecialist::scanSW(), RasterSpecialist::scanWest(), GT2004FlagSpecialist::searchFlags(), BoxSpecialist::searchGoal(), BoxSpecialist::searchLandmark(), CircleCalculation::select3Points(), GT2004BallLocator::setBallStateV2(), REdgeDetection::setDirection(), BresenhamLineScan::setup(), GT2004HeadControl::simpleLookAtPointRelativeToRobot(), horLinePair::size(), RasterSpecialist::theta(), theta2(), horLinePair::toConsider(), OpenChallengeSymbols::update(), KalmanConstantSpeedModel::update(), GT2004SelfLocator::updateByFlag(), GT2004SelfLocator::updateByGoalPost(), GT2004SelfLocator::updateByPoint(), BB2004InvKinWalkingEngine::updateOdometry(), FieldDimensions::vectorToBorder(), FieldDimensions::vectorToBorderIncludingGoals(), and TeamMessage::write().

template<class V>
V Vector2< V >::y
 

The vector values.

Definition at line 19 of file Vector2.h.

Referenced by KalmanFixedPositionModel::adapt(), KalmanConstantSpeedModel::adapt(), Boundary< double >::add(), RBallSpecialist2::addBallPercept(), GT2004BallSpecialist::addBallPercept(), Field::addCoords(), LandmarksPercept::addFlag(), RasterImageProcessor::addFlag(), LandmarksPercept::addGoal(), RasterImageProcessor::addObstaclePoints(), GT2004PlayersLocator::addOppPlayerPercepts(), GT2004PlayersLocator::addOwnPlayerPercepts(), Field::addPlayer(), GT2004ObstaclesLocator::addPSDPercept(), RFieldSpecialist::analyzeLines(), GT2004HeadControl::beginBallSearchAt(), GT2004ImageProcessor::calcEdgeAngle(), Geometry::calculateBallInImage(), REnemySpecialist::calculateFarestPoint(), REnemySpecialist::calculateFarestPointCOG(), REnemySpecialist::calculateFarestPointFastCOG(), RBallSpecialist2::calculateLargeCircle(), Geometry::calculatePointInImage(), Geometry::calculatePointOnField(), GoalRecognizer::calculateVerticalGoalScanLines(), GT2004GoalRecognizer::calculateVerticalGoalScanLines(), RasterStrategy::checkColor(), RasterSpecialist::checkColor(), BallPercept::checkOffset(), RFieldSpecialist::checkRamp(), FieldDimensions::clipLineWithField(), FieldDimensions::clipLineWithFieldAndGoalAreas(), Geometry::clipLineWithQuadrangle(), Geometry::clipLineWithRectangleCohenSutherland(), Geometry::clipPointInsideRectange(), GT2004BeaconDetector::clusterPinkBeaconParts(), GT2004ImageProcessor::clusterRobots(), Geometry::cohenSutherlandOutCode(), GT2004BallLocator::compensateOdometry(), ObservationTable< 280, 200, 25 >::create(), RBridgeSpecialist::createBBox(), BoxSpecialist::createBBox(), CircleCalculation::createCircle(), CircleCalculation::cutMiddlePerpendiculars(), BoxSpecialist::detectFreePartOfGoal(), FieldDimensions::distanceToBorder(), FieldDimensions::distanceToOpponentPenaltyArea(), Field::draw(), GT2004SelfLocator::draw(), GT2004BallLocator::drawBallPosition(), RFieldSpecialist::drawCircle(), RFieldSpecialist::drawCross(), RFieldSpecialist::drawLine(), MotionRecognition::drawPixelFlow(), edge::edge(), GT2004ImageProcessor::execute(), GT2004BeaconDetector::execute(), CheckerboardDetector::execute(), GT2004BasicBehaviorDirectedScanForLandmarks::execute(), GT2004BasicBehaviorTurnAroundPoint::execute(), GT2004BasicBehaviorGoaliePosition::execute(), GT2004BasicBehaviorGoToBallWithoutTurning::execute(), GT2004BasicBehaviorGoToBall::execute(), GT2004PotentialFieldBasicBehaviorGoToPose::execute(), REnemySpecialist::executePostProcessing(), ChallengeSpecialVision::executeReset(), Geometry::fieldCoord2Relative(), RBridgeSpecialist::findBridgeMark(), GT2004FlagSpecialist::findEndOfFlag(), REdgeDetection::findStart(), BoxSpecialist::fitLandmark(), GT2004SelfLocator::generatePoseTemplates(), CheckerboardDetector::getAngleBetweenScreenPoints(), MotionRecognition::getAngleYZ(), MotionRecognition::getCenteredCoor(), RasterStrategy::getColor(), RasterSpecialist::getColor(), MotionRecognition::getCoorInmm(), MotionRecognition::getCoorInPixel(), extLinePair::getDirection(), Field::getDistance(), Geometry::getDistanceToLine(), RasterSpecialist::getDistanceToLine(), Field::getDistanceToOwnPenaltyArea(), GT2004EdgeSpecialist::getEdgesPercept(), CheckerboardDetector::getExactTransitionMiddle(), GT2004FlagSpecialist::getFlagPercept(), horLinePair::getId(), Geometry::getIntersectionOfLines(), Geometry::getIntersectionPointsOfLineAndRectangle(), GT2004HeadControl::getLookAtBallAngles(), CheckerboardDetector::getMiddleAndLengthOfPerpendicular(), BallPercept::getOffsetBearingBased(), BallPercept::getOffsetIntrinsic(), BallPercept::getOffsetSizeBased(), MotionRecognition::getPixelDiff(), MotionRecognition::getPixelFlow(), RBridgeSpecialist::getPosition(), CheckerboardDetector::getPositionFromAngles(), MotionRecognition::getRobotTranslationFromOdometry(), GT2004BallLocator::handleSeenBall(), GT2004BallLocator::handleUnseenBall(), RFieldSpecialist::invokeOnPreScan(), MotionRecognition::isDiff(), Boundary< double >::isInside(), FieldDimensions::isInsideField(), FieldDimensions::isInsideGoal(), FieldDimensions::isInsideOpponentGoal(), FieldDimensions::isInsideOwnGoal(), FieldDimensions::isOnOpponentGoalGroundline(), FieldDimensions::isOnOwnGoalGroundline(), RasterImageProcessor::isValidPoint(), Geometry::Line::Line(), LinesPercept::LinePoint::LinePoint(), makeLine(), mil(), Vector2< int >::operator *(), Matrix2x2< double >::operator *(), Matrix2x2< double >::operator+(), Vector2< int >::operator+=(), Matrix2x2< double >::operator-(), Vector2< int >::operator-=(), LinePair2::operator<(), Vector2< int >::operator=(), LinesPercept::LinePoint::operator=(), SeenBallPosition::operator=(), GT2004BallSpecialist::BallPoint::operator=(), Vector2< int >::operator==(), operator>>(), MotionRecognition::pixelInImage(), GT2004ImageProcessor::plot(), GT2004SelfLocator::poseFromBearings(), GT2004SelfLocator::poseFromBearingsAndDistance(), RDefaultStrategy::postScan(), RDefaultStrategy::preScan(), horLinePair::pt2(), TeamMessage::read(), Geometry::relative2FieldCoord(), RasterSpecialist::scan(), GT2004ImageProcessor::scan(), GT2004ImageProcessor::scanColumns(), RasterSpecialist::scanEast(), GT2004BallSpecialist::scanForBallPoints(), GT2004BeaconDetector::scanForBeaconEdges(), GT2004BeaconDetector::scanForBeaconPart(), GT2004BeaconDetector::scanForPink(), GoalRecognizer::scanHorizontalForGoals(), GT2004GoalRecognizer::scanHorizontalForGoals(), GoalRecognizer::scanLinesForGoals(), GT2004GoalRecognizer::scanLinesForGoals(), RasterSpecialist::scanNE(), RasterSpecialist::scanNorth(), RasterSpecialist::scanNW(), GT2004ImageProcessor::scanRows(), RasterSpecialist::scanSE(), RasterSpecialist::scanSouth(), RasterSpecialist::scanSW(), RasterSpecialist::scanWest(), GT2004FlagSpecialist::searchFlags(), BoxSpecialist::searchGoal(), BoxSpecialist::searchLandmark(), CircleCalculation::select3Points(), GT2004BallLocator::setBallStateV2(), REdgeDetection::setDirection(), BresenhamLineScan::setup(), GT2004HeadControl::simpleLookAtPointRelativeToRobot(), RasterSpecialist::theta(), theta2(), horLinePair::toConsider(), Matrix2x2< double >::transpose(), OpenChallengeSymbols::update(), KalmanConstantSpeedModel::update(), GT2004SelfLocator::updateByFlag(), GT2004SelfLocator::updateByGoalPost(), GT2004SelfLocator::updateByPoint(), BB2004InvKinWalkingEngine::updateOdometry(), FieldDimensions::vectorToBorder(), FieldDimensions::vectorToBorderIncludingGoals(), and TeamMessage::write().


The documentation for this class was generated from the following file:
Generated on Thu Sep 23 20:12:11 2004 for GT2004 by doxygen 1.3.6