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

GT2004HeadControl Class Reference

The GT2004 version of the HeadControl module. More...

#include <GT2004HeadControl.h>

Inheritance diagram for GT2004HeadControl:

Inheritance graph
[legend]
Collaboration diagram for GT2004HeadControl:

Collaboration graph
[legend]
List of all members.

Public Types

enum  { minHeadSpeed = 4000 }
 The minimum head speed in urad per frame: 4000 = 28.6°/s. More...

enum  {
  calibrationStateStart, calibrationStateLeft, calibrationStateLeftWait,
  calibrationStateRight, calibrationStateRightWait, calibrationStateDownTilt1,
  calibrationStateDownTilt1Wait, calibrationStateUpTilt1, calibrationStateUpTilt1Wait,
  calibrationStateDownTilt2, calibrationStateDownTilt2Wait, calibrationStateUpTilt2,
  calibrationStateUpTilt2Wait, calibrationStateUseResults, calibrationStateReady
}

Public Member Functions

 GT2004HeadControl (HeadControlInterfaces &interfaces)
 Constructor.

 ~GT2004HeadControl ()
 Destructor.

virtual void execute ()
 Executes the module.

virtual bool handleMessage (InMessage &message)
 Is called for every incoming debug message.

virtual void registerSymbolsAndBasicBehaviors ()
 Registers symbols and basic behaviors at the engine.

bool headPanIsLeft ()
 Is true, if the head is on the left side.

void getSensorHeadAngles (Vector3< double > &pos)
 put the sensor values in var pos

double headPositionDistanceToActualPosition (Vector3< double > comp, bool leftSide)
 returns a distance between actual position and comp.

void setJoints (double tilt, double pan, double roll, double speed=0, double mouth=0)
 deals with setting the head joints and performs optimizations so that the head does not move too fast angles are in RAD and NOT EVER AGAIN(!!) IN MICRORAD!

void setJointsDirect (double tilt, double pan, double roll, double mouth=0)
void simpleLookAtPointRelativeToRobot (const Vector3< double > pos, Vector2< int > offset, double &neckTilt, double &headPan, double &headTilt)
void simpleLookAtPointOnField (const Vector3< double > pos, Vector2< int > offset, double &neckTilt, double &headPan, double &headTilt)
 Simplified "look at 3d-point" on field with offset point in camera image this is straight-forward for the ERS210, but the ERS7 has two tilt joints that can both be used to look at something.

bool simpleLookAtPointFixNeckTilt (const Vector3< double > &aim, const double &tilt1, double &headPan, double &headTilt)
 Simplified "look at 3d-point" subroutine trying to find tilt1 solution for given tilt2/roll.

void lookAtPoint (const Vector3< double > &pos, const Vector2< int > &offset, double &tilt, double &pan, double &roll)
 look at 3d-point on field with offset point in camera image this is straight-forward for the ERS210, but the ERS7 has two tilt joints that can both be used to look at something.

bool lookAtPointFixHeadTilt (const Vector3< double > &aim, const double &xtan, const double &ytan, double &tilt1, double &pan, const double &tilt2)
 look at 3d-point subroutine trying to find tilt1 solution for given tilt2/roll.

bool lookAtPointFixNeckTilt (const Vector3< double > &aim, const double &xtan, const double &ytan, const double &tilt, double &pan, double &tilt2)
 look at 3d-point subroutine trying to find tilt2 solution for given tilt1.

int calculateClosestLandmark (double direction=0, double nextLeftOrRight=0)
 return the closest landmark w.r.t.

void aimAtLandmark (int landmark, double &neckTilt, double &headPan, double &headTilt)
 call look-at-point depending on whether the landmark has has a z-dimension the offset in the image is adjusted: landmarks on the ground are aimed at differently from goals and corner posts

void getLookAtBallAngles (const Vector2< double > ballOnField, double &neckTilt, double &headPan, double &headTilt)
 returns the angles that are good for looking at the ball

void setupMainAngles ()
 initial the main angles for the head movement

void calibrateHeadSpeed ()
void calibrationReset ()
bool headPositionReached (Vector3< double > pos)
int getLastSeenBeaconIndex ()
 return the index of the last seen beacon

long getTimeOfLastSeenBeacon (int index)
 return the time of the last seen beacon

long getTimeBetweenSeen2LastBeacons (int index)
 return the time between the two last seen beacons

bool isTimedOut ()
bool calibrateHeadSpeedIsReady ()
void searchForBallLeft ()
 looks to the left/right side an aearch for ball.

void searchForBallRight ()
void beginBallSearchAt (Vector2< double > ballPosition2d)
 begin a ball search by the given start position


Public Attributes

GT2004HeadPathPlanner headPathPlanner
 An instance of the head path planner.

bool lastScanWasLeft
 If true, the last head movement was directed to the left side (of the ball).

HeadControlMode::HeadControlModes lastHeadControlMode
 The head control mode that was executed in the last frame.

CameraInfo cameraInfo
 Information about the used camera.

GT2004HeadControlSymbols symbols
 The symbols used by the Xabsl2Engine.

GT2004HeadControlBasicBehaviors basicBehaviors
 The basic behaviors used by the Xabsl2Engine.

int setJointsIsCloseToDestination
 stores the number of frames "setjoints" has been close to its destination

bool setJointsMaxPanReached
 true if the max pan of the head joint is reached

Vector3< double > headLeft
 basic headpositions for the gaze

Vector3< double > headRight
Vector3< double > headMiddleLeft
Vector3< double > headMiddleLeftDown
Vector3< double > headMiddleRight
Vector3< double > headMiddleRightDown
Vector3< double > headRightDown
Vector3< double > headLeftDown
Vector3< double > headUp
Vector3< double > headDown
double speedNeckTilt
 speed in rad/s for head movement.

double speedHeadPan
double speedHeadTilt
bool useCommunicatedBall
enum GT2004HeadControl:: { ... }  calibrationState
long calibrationTime
int calibrationTimeOutsTilt1
int calibrationTimeOutsPan
int calibrationTimeOutsTilt2
int calibrationRoundCount
int calibrationSuccessfulRounds

Private Attributes

Range< double > jointRangeNeckTilt
Range< double > jointRangeHeadPan
Range< double > jointRangeHeadTilt
OdometryData lastOdometryData
RobotPose lastRobotPose

Detailed Description

The GT2004 version of the HeadControl module.

Author:
Marc Dassler

Jan Hoffmann

Uwe Düffert

Martin Lötzsch

Definition at line 31 of file GT2004HeadControl.h.


Member Enumeration Documentation

anonymous enum
 

The minimum head speed in urad per frame: 4000 = 28.6°/s.

Enumeration values:
minHeadSpeed 

Definition at line 84 of file GT2004HeadControl.h.

anonymous enum
 

Enumeration values:
calibrationStateStart 
calibrationStateLeft 
calibrationStateLeftWait 
calibrationStateRight 
calibrationStateRightWait 
calibrationStateDownTilt1 
calibrationStateDownTilt1Wait 
calibrationStateUpTilt1 
calibrationStateUpTilt1Wait 
calibrationStateDownTilt2 
calibrationStateDownTilt2Wait 
calibrationStateUpTilt2 
calibrationStateUpTilt2Wait 
calibrationStateUseResults 
calibrationStateReady 

Definition at line 168 of file GT2004HeadControl.h.


Constructor & Destructor Documentation

GT2004HeadControl::GT2004HeadControl HeadControlInterfaces interfaces  ) 
 

Constructor.

Parameters:
interfaces The paramters of the HeadControl module.

Definition at line 26 of file GT2004HeadControl.cpp.

References calibrationReset(), CameraInfo::CameraInfo(), SensorData::data, getRobotConfiguration(), RobotConfiguration::getRobotDimensions(), headPathPlanner, GT2004HeadPathPlanner::headPathSpeedHeadPan, GT2004HeadPathPlanner::headPathSpeedHeadTilt, GT2004HeadPathPlanner::headPathSpeedNeckTilt, GTXabsl2EngineExecutor::init(), RobotDimensions::jointLimitHeadPanN, RobotDimensions::jointLimitHeadPanP, RobotDimensions::jointLimitHeadTiltN, RobotDimensions::jointLimitHeadTiltP, RobotDimensions::jointLimitNeckTiltN, RobotDimensions::jointLimitNeckTiltP, jointRangeHeadPan, jointRangeHeadTilt, jointRangeNeckTilt, SensorDataBuffer::lastFrame(), GT2004HeadPathPlanner::lastHeadPan, GT2004HeadPathPlanner::lastHeadTilt, GT2004HeadPathPlanner::lastNeckTilt, setupMainAngles(), speedHeadPan, speedHeadTilt, speedNeckTilt, and useCommunicatedBall.

Here is the call graph for this function:

GT2004HeadControl::~GT2004HeadControl  )  [inline]
 

Destructor.

Definition at line 41 of file GT2004HeadControl.h.


Member Function Documentation

void GT2004HeadControl::execute  )  [virtual]
 

Executes the module.

Implements Module.

Definition at line 134 of file GT2004HeadControl.cpp.

References SensorData::data, GTXabsl2EngineExecutor::executeEngine(), RobotState::getButtonDuration(), RobotState::getButtonPressed(), HeadControlMode::headControlMode, headPathPlanner, SensorDataBuffer::lastFrame(), lastHeadControlMode, GT2004HeadPathPlanner::lastHeadPan, GT2004HeadPathPlanner::lastHeadTilt, GT2004HeadPathPlanner::lastNeckTilt, GTXabsl2Profiler::profilerCollectMode, GTXabsl2Profiler::profilerWriteMode, symbols, and GT2004HeadControlSymbols::update().

Here is the call graph for this function:

bool GT2004HeadControl::handleMessage InMessage message  )  [virtual]
 

Is called for every incoming debug message.

Parameters:
message An interface to read the message from the queue
Returns:
if the messag was read

Reimplemented from Xabsl2HeadControl.

Definition at line 173 of file GT2004HeadControl.cpp.

References Xabsl2HeadControl::handleMessage().

Here is the call graph for this function:

void GT2004HeadControl::registerSymbolsAndBasicBehaviors  )  [virtual]
 

Registers symbols and basic behaviors at the engine.

Implements GTXabsl2EngineExecutor.

Definition at line 128 of file GT2004HeadControl.cpp.

References GT2004HeadControlBasicBehaviors::registerBasicBehaviors(), GT2004HeadControlSymbols::registerSymbols(), and symbols.

Here is the call graph for this function:

bool GT2004HeadControl::headPanIsLeft  ) 
 

Is true, if the head is on the left side.

Definition at line 82 of file GT2004HeadControl.cpp.

References SensorData::data, and SensorDataBuffer::lastFrame().

Here is the call graph for this function:

void GT2004HeadControl::getSensorHeadAngles Vector3< double > &  pos  ) 
 

put the sensor values in var pos

Definition at line 87 of file GT2004HeadControl.cpp.

References SensorData::data, SensorDataBuffer::lastFrame(), Vector3< V >::x, Vector3< V >::y, and Vector3< V >::z.

Here is the call graph for this function:

double GT2004HeadControl::headPositionDistanceToActualPosition Vector3< double >  comp,
bool  leftSide
 

returns a distance between actual position and comp.

the small results are better

Definition at line 120 of file GT2004HeadControl.cpp.

References SensorData::data, SensorDataBuffer::lastFrame(), and Vector3< V >::y.

Here is the call graph for this function:

void GT2004HeadControl::setJoints double  tilt,
double  pan,
double  roll,
double  speed = 0,
double  mouth = 0
 

deals with setting the head joints and performs optimizations so that the head does not move too fast angles are in RAD and NOT EVER AGAIN(!!) IN MICRORAD!

Definition at line 243 of file GT2004HeadControl.cpp.

References Vector2< double >::abs(), Vector2< V >::abs(), direction, headPathPlanner, GT2004HeadPathPlanner::headPositionReached(), jointRangeHeadPan, jointRangeHeadTilt, jointRangeNeckTilt, GT2004HeadPathPlanner::lastHeadPan, GT2004HeadPathPlanner::lastHeadTilt, GT2004HeadPathPlanner::lastNeckTilt, lastOdometryData, Range< double >::limit(), Range< double >::max, HeadMotionRequest::mouth, Vector2< V >::normalize(), HeadMotionRequest::pan, HeadMotionRequest::roll, setJointsIsCloseToDestination, setJointsMaxPanReached, HeadMotionRequest::tilt, Vector2< double >::x, and Vector2< double >::y.

Referenced by GT2004BasicBehaviorDirectedScanForLandmarks::execute().

Here is the call graph for this function:

void GT2004HeadControl::setJointsDirect double  tilt,
double  pan,
double  roll,
double  mouth = 0
 

Definition at line 231 of file GT2004HeadControl.cpp.

References headPathPlanner, jointRangeHeadPan, jointRangeHeadTilt, jointRangeNeckTilt, GT2004HeadPathPlanner::lastHeadPan, GT2004HeadPathPlanner::lastHeadTilt, GT2004HeadPathPlanner::lastNeckTilt, Range< double >::limit(), HeadMotionRequest::mouth, HeadMotionRequest::pan, HeadMotionRequest::roll, HeadMotionRequest::tilt, and toMicroRad().

Here is the call graph for this function:

void GT2004HeadControl::simpleLookAtPointRelativeToRobot const Vector3< double >  pos,
Vector2< int >  offset,
double &  neckTilt,
double &  headPan,
double &  headTilt
 

Definition at line 341 of file GT2004HeadControl.cpp.

References BodyPosture::bodyRollCalculatedFromLegSensors, BodyPosture::bodyTiltCalculatedFromLegSensors, jointRangeHeadPan, jointRangeHeadTilt, jointRangeNeckTilt, Range< T >::limit(), BodyPosture::neckHeightCalculatedFromLegSensors, CameraInfo::openingAngleHeight, CameraInfo::openingAngleWidth, CameraInfo::resolutionHeight, CameraInfo::resolutionWidth, RotationMatrix::rotateY(), simpleLookAtPointFixNeckTilt(), Vector2< V >::x, Vector2< V >::y, and Vector3< V >::z.

Referenced by getLookAtBallAngles(), and simpleLookAtPointOnField().

Here is the call graph for this function:

void GT2004HeadControl::simpleLookAtPointOnField const Vector3< double >  pos,
Vector2< int >  offset,
double &  neckTilt,
double &  headPan,
double &  headTilt
 

Simplified "look at 3d-point" on field with offset point in camera image this is straight-forward for the ERS210, but the ERS7 has two tilt joints that can both be used to look at something.

Lookatpoint uses the two following methods to find a 'good' solution.

transform the targets position to the robot's "coord. system":

transform from world to relative coordinates

what about the order of the rotations?

rotate by the body's rotation(s)

Definition at line 393 of file GT2004HeadControl.cpp.

References Pose2D::getAngle(), RotationMatrix::rotateZ(), simpleLookAtPointRelativeToRobot(), Pose2D::translation, Vector2< double >::x, Vector3< V >::x, Vector2< double >::y, and Vector3< V >::y.

Referenced by aimAtLandmark(), and beginBallSearchAt().

Here is the call graph for this function:

bool GT2004HeadControl::simpleLookAtPointFixNeckTilt const Vector3< double > &  aim,
const double &  tilt1,
double &  headPan,
double &  headTilt
 

Simplified "look at 3d-point" subroutine trying to find tilt1 solution for given tilt2/roll.

this is useful on ERS210 and ERS7

Returns:
true when matching angles were found

transformation from "neck-coord" into cam. coord., i.e.

translation by distanceNeckToPanCenter

a rotation by the neck-joint Angle followed by

get the pan angle from looking at where the target is in the xy plane

never mind clipping: if (headPan>=pi) headPan -= pi2; else if (headPan<-pi) headPan += pi2;

perform (pan-) rotation on target

get the headTilt angle by taking the angle to the target in the XZ-Plane

again, no clipping: if (headTilt >= pi) headTilt -= pi2; else if (headTilt < -pi) headTilt += pi2;

For debugging: Rotate camera coord. system by the tilt just found. If everything was done correctly, target should have y = z = 0.0

RotationMatrix rotationByHeadTilt; rotationByHeadTilt.rotateY(headTilt); target = rotationByHeadTilt*target;

if values are our of bounds, return 0 so a different method can be applied!

Definition at line 410 of file GT2004HeadControl.cpp.

References RotationMatrix::rotateY(), RotationMatrix::rotateZ(), and Vector3< V >::z.

Referenced by simpleLookAtPointRelativeToRobot().

Here is the call graph for this function:

void GT2004HeadControl::lookAtPoint const Vector3< double > &  pos,
const Vector2< int > &  offset,
double &  tilt,
double &  pan,
double &  roll
 

look at 3d-point on field with offset point in camera image this is straight-forward for the ERS210, but the ERS7 has two tilt joints that can both be used to look at something.

Lookatpoint uses the two following methods to find a 'good' solution.

bool GT2004HeadControl::lookAtPointFixHeadTilt const Vector3< double > &  aim,
const double &  xtan,
const double &  ytan,
double &  tilt1,
double &  pan,
const double &  tilt2
 

look at 3d-point subroutine trying to find tilt1 solution for given tilt2/roll.

this is useful on ERS210 and ERS7

Returns:
true when matching angles were found

bool GT2004HeadControl::lookAtPointFixNeckTilt const Vector3< double > &  aim,
const double &  xtan,
const double &  ytan,
const double &  tilt,
double &  pan,
double &  tilt2
 

look at 3d-point subroutine trying to find tilt2 solution for given tilt1.

this is only useful on ERS7

Returns:
true when matching angles were found

int GT2004HeadControl::calculateClosestLandmark double  direction = 0,
double  nextLeftOrRight = 0
 

return the closest landmark w.r.t.

a given direction; also, the next landmark to the left (or right) can be calculated.

Definition at line 439 of file GT2004HeadControl.cpp.

References Vector2< V >::abs(), Vector2< V >::angle(), CIRCLE, LINE, normalize(), Pose2D::rotation, sgn, Pose2D::translation, Vector2< double >::x, and Vector2< double >::y.

Referenced by GT2004BasicBehaviorDirectedScanForLandmarks::execute().

Here is the call graph for this function:

void GT2004HeadControl::aimAtLandmark int  landmark,
double &  neckTilt,
double &  headPan,
double &  headTilt
 

call look-at-point depending on whether the landmark has has a z-dimension the offset in the image is adjusted: landmarks on the ground are aimed at differently from goals and corner posts

Definition at line 302 of file GT2004HeadControl.cpp.

References CameraInfo::resolutionHeight, and simpleLookAtPointOnField().

Referenced by GT2004BasicBehaviorDirectedScanForLandmarks::execute().

Here is the call graph for this function:

void GT2004HeadControl::getLookAtBallAngles const Vector2< double >  ballOnField,
double &  neckTilt,
double &  headPan,
double &  headTilt
 

returns the angles that are good for looking at the ball

Definition at line 322 of file GT2004HeadControl.cpp.

References Vector2< V >::abs(), Geometry::fieldCoord2Relative(), Range< T >::limit(), CameraInfo::resolutionHeight, simpleLookAtPointRelativeToRobot(), Vector2< V >::x, and Vector2< V >::y.

Here is the call graph for this function:

void GT2004HeadControl::setupMainAngles  ) 
 

initial the main angles for the head movement

Definition at line 490 of file GT2004HeadControl.cpp.

References headDown, headLeftDown, headMiddleLeft, headMiddleLeftDown, headMiddleRight, headMiddleRightDown, headRightDown, headUp, Vector3< double >::x, Vector3< double >::y, and Vector3< double >::z.

Referenced by GT2004HeadControl().

void GT2004HeadControl::calibrateHeadSpeed  ) 
 

Definition at line 534 of file GT2004HeadControl.cpp.

References calibrationRoundCount, calibrationState, calibrationStateDownTilt1, calibrationStateDownTilt1Wait, calibrationStateDownTilt2, calibrationStateDownTilt2Wait, calibrationStateLeft, calibrationStateLeftWait, calibrationStateReady, calibrationStateRight, calibrationStateRightWait, calibrationStateStart, calibrationStateUpTilt1, calibrationStateUpTilt1Wait, calibrationStateUpTilt2, calibrationStateUpTilt2Wait, calibrationStateUseResults, calibrationSuccessfulRounds, calibrationTime, calibrationTimeOutsPan, calibrationTimeOutsTilt1, calibrationTimeOutsTilt2, SystemCall::getCurrentSystemTime(), SystemCall::getTimeSince(), headPathPlanner, GT2004HeadPathPlanner::headPathSpeedHeadPan, GT2004HeadPathPlanner::headPathSpeedHeadTilt, GT2004HeadPathPlanner::headPathSpeedNeckTilt, headPositionReached(), headUp, idText, GT2004HeadPathPlanner::init(), GT2004HeadPathPlanner::isLastPathFinished(), isTimedOut(), OUTPUT, speedHeadPan, speedHeadTilt, speedNeckTilt, Vector3< V >::x, Vector3< V >::y, and Vector3< V >::z.

Here is the call graph for this function:

void GT2004HeadControl::calibrationReset  )  [inline]
 

Definition at line 191 of file GT2004HeadControl.h.

References calibrationState, calibrationStateStart, calibrationTimeOutsPan, calibrationTimeOutsTilt1, and calibrationTimeOutsTilt2.

Referenced by GT2004HeadControl().

bool GT2004HeadControl::headPositionReached Vector3< double >  pos  )  [inline]
 

Definition at line 199 of file GT2004HeadControl.h.

References headPathPlanner, and GT2004HeadPathPlanner::headPositionReached().

Referenced by calibrateHeadSpeed().

Here is the call graph for this function:

int GT2004HeadControl::getLastSeenBeaconIndex  ) 
 

return the index of the last seen beacon

Definition at line 68 of file GT2004HeadControl.cpp.

References LandmarksState::lastSeenBeaconIndex().

Referenced by GT2004HeadControlSymbols::update().

Here is the call graph for this function:

long GT2004HeadControl::getTimeOfLastSeenBeacon int  index  ) 
 

return the time of the last seen beacon

Definition at line 72 of file GT2004HeadControl.cpp.

References LandmarksState::timeOfLastSeenBeacon().

Referenced by GT2004HeadControlSymbols::getTimeSinceLastSeenABeacon().

Here is the call graph for this function:

long GT2004HeadControl::getTimeBetweenSeen2LastBeacons int  index  ) 
 

return the time between the two last seen beacons

Definition at line 77 of file GT2004HeadControl.cpp.

References LandmarksState::timeBetweenSeen2LastBeacons().

Referenced by GT2004HeadControlSymbols::getTimeBetweenSeen2LastBeacons().

Here is the call graph for this function:

bool GT2004HeadControl::isTimedOut  )  [inline]
 

Definition at line 214 of file GT2004HeadControl.h.

References calibrationTime, and SystemCall::getTimeSince().

Referenced by calibrateHeadSpeed().

Here is the call graph for this function:

bool GT2004HeadControl::calibrateHeadSpeedIsReady  )  [inline]
 

Definition at line 219 of file GT2004HeadControl.h.

References calibrationState, and calibrationStateReady.

void GT2004HeadControl::searchForBallLeft  ) 
 

looks to the left/right side an aearch for ball.

Used for kicks

Definition at line 107 of file GT2004HeadControl.cpp.

References headDown, headMiddleLeft, headPathPlanner, GT2004HeadPathPlanner::init(), and lastScanWasLeft.

Here is the call graph for this function:

void GT2004HeadControl::searchForBallRight  ) 
 

Definition at line 94 of file GT2004HeadControl.cpp.

References headDown, headMiddleRight, headPathPlanner, GT2004HeadPathPlanner::init(), and lastScanWasLeft.

Here is the call graph for this function:

void GT2004HeadControl::beginBallSearchAt Vector2< double >  ballPosition2d  ) 
 

begin a ball search by the given start position

Definition at line 179 of file GT2004HeadControl.cpp.

References headDown, headLeftDown, headMiddleLeft, headMiddleLeftDown, headMiddleRight, headMiddleRightDown, headPathPlanner, headRightDown, headUp, GT2004HeadPathPlanner::init(), lastScanWasLeft, normalize(), Pose2D::rotation, simpleLookAtPointOnField(), Pose2D::translation, Vector2< V >::x, and Vector2< V >::y.

Here is the call graph for this function:


Member Data Documentation

GT2004HeadPathPlanner GT2004HeadControl::headPathPlanner
 

An instance of the head path planner.

Definition at line 57 of file GT2004HeadControl.h.

Referenced by beginBallSearchAt(), calibrateHeadSpeed(), execute(), GT2004HeadControlSymbols::getLastHeadPathIsFinished(), GT2004HeadControl(), headPositionReached(), searchForBallLeft(), searchForBallRight(), setJoints(), and setJointsDirect().

bool GT2004HeadControl::lastScanWasLeft
 

If true, the last head movement was directed to the left side (of the ball).

Definition at line 60 of file GT2004HeadControl.h.

Referenced by beginBallSearchAt(), searchForBallLeft(), and searchForBallRight().

HeadControlMode::HeadControlModes GT2004HeadControl::lastHeadControlMode
 

The head control mode that was executed in the last frame.

Definition at line 72 of file GT2004HeadControl.h.

Referenced by execute().

CameraInfo GT2004HeadControl::cameraInfo
 

Information about the used camera.

Definition at line 75 of file GT2004HeadControl.h.

GT2004HeadControlSymbols GT2004HeadControl::symbols
 

The symbols used by the Xabsl2Engine.

Definition at line 78 of file GT2004HeadControl.h.

Referenced by execute(), and registerSymbolsAndBasicBehaviors().

GT2004HeadControlBasicBehaviors GT2004HeadControl::basicBehaviors
 

The basic behaviors used by the Xabsl2Engine.

Definition at line 81 of file GT2004HeadControl.h.

int GT2004HeadControl::setJointsIsCloseToDestination
 

stores the number of frames "setjoints" has been close to its destination

Definition at line 134 of file GT2004HeadControl.h.

Referenced by GT2004HeadControlSymbols::getSetJointsIsCloseToDestination(), and setJoints().

bool GT2004HeadControl::setJointsMaxPanReached
 

true if the max pan of the head joint is reached

Definition at line 137 of file GT2004HeadControl.h.

Referenced by GT2004HeadControlSymbols::getSetJointsMaxPanReached(), and setJoints().

Vector3<double> GT2004HeadControl::headLeft
 

basic headpositions for the gaze

Definition at line 144 of file GT2004HeadControl.h.

Vector3<double> GT2004HeadControl::headRight
 

Definition at line 145 of file GT2004HeadControl.h.

Vector3<double> GT2004HeadControl::headMiddleLeft
 

Definition at line 146 of file GT2004HeadControl.h.

Referenced by beginBallSearchAt(), searchForBallLeft(), and setupMainAngles().

Vector3<double> GT2004HeadControl::headMiddleLeftDown
 

Definition at line 147 of file GT2004HeadControl.h.

Referenced by beginBallSearchAt(), and setupMainAngles().

Vector3<double> GT2004HeadControl::headMiddleRight
 

Definition at line 148 of file GT2004HeadControl.h.

Referenced by beginBallSearchAt(), searchForBallRight(), and setupMainAngles().

Vector3<double> GT2004HeadControl::headMiddleRightDown
 

Definition at line 149 of file GT2004HeadControl.h.

Referenced by beginBallSearchAt(), and setupMainAngles().

Vector3<double> GT2004HeadControl::headRightDown
 

Definition at line 150 of file GT2004HeadControl.h.

Referenced by beginBallSearchAt(), and setupMainAngles().

Vector3<double> GT2004HeadControl::headLeftDown
 

Definition at line 151 of file GT2004HeadControl.h.

Referenced by beginBallSearchAt(), and setupMainAngles().

Vector3<double> GT2004HeadControl::headUp
 

Definition at line 152 of file GT2004HeadControl.h.

Referenced by beginBallSearchAt(), calibrateHeadSpeed(), and setupMainAngles().

Vector3<double> GT2004HeadControl::headDown
 

Definition at line 153 of file GT2004HeadControl.h.

Referenced by beginBallSearchAt(), searchForBallLeft(), searchForBallRight(), and setupMainAngles().

double GT2004HeadControl::speedNeckTilt
 

speed in rad/s for head movement.

its used for headpathplanner and the calibration

Definition at line 156 of file GT2004HeadControl.h.

Referenced by calibrateHeadSpeed(), and GT2004HeadControl().

double GT2004HeadControl::speedHeadPan
 

Definition at line 157 of file GT2004HeadControl.h.

Referenced by calibrateHeadSpeed(), and GT2004HeadControl().

double GT2004HeadControl::speedHeadTilt
 

Definition at line 158 of file GT2004HeadControl.h.

Referenced by calibrateHeadSpeed(), and GT2004HeadControl().

bool GT2004HeadControl::useCommunicatedBall
 

Definition at line 166 of file GT2004HeadControl.h.

Referenced by GT2004HeadControl().

enum { ... } GT2004HeadControl::calibrationState
 

Referenced by calibrateHeadSpeed(), calibrateHeadSpeedIsReady(), and calibrationReset().

long GT2004HeadControl::calibrationTime
 

Definition at line 187 of file GT2004HeadControl.h.

Referenced by calibrateHeadSpeed(), and isTimedOut().

int GT2004HeadControl::calibrationTimeOutsTilt1
 

Definition at line 188 of file GT2004HeadControl.h.

Referenced by calibrateHeadSpeed(), and calibrationReset().

int GT2004HeadControl::calibrationTimeOutsPan
 

Definition at line 188 of file GT2004HeadControl.h.

Referenced by calibrateHeadSpeed(), and calibrationReset().

int GT2004HeadControl::calibrationTimeOutsTilt2
 

Definition at line 188 of file GT2004HeadControl.h.

Referenced by calibrateHeadSpeed(), and calibrationReset().

int GT2004HeadControl::calibrationRoundCount
 

Definition at line 189 of file GT2004HeadControl.h.

Referenced by calibrateHeadSpeed().

int GT2004HeadControl::calibrationSuccessfulRounds
 

Definition at line 189 of file GT2004HeadControl.h.

Referenced by calibrateHeadSpeed().

Range<double> GT2004HeadControl::jointRangeNeckTilt [private]
 

Definition at line 232 of file GT2004HeadControl.h.

Referenced by GT2004HeadControl(), setJoints(), setJointsDirect(), and simpleLookAtPointRelativeToRobot().

Range<double> GT2004HeadControl::jointRangeHeadPan [private]
 

Definition at line 232 of file GT2004HeadControl.h.

Referenced by GT2004HeadControl(), setJoints(), setJointsDirect(), and simpleLookAtPointRelativeToRobot().

Range<double> GT2004HeadControl::jointRangeHeadTilt [private]
 

Definition at line 232 of file GT2004HeadControl.h.

Referenced by GT2004HeadControl(), setJoints(), setJointsDirect(), and simpleLookAtPointRelativeToRobot().

OdometryData GT2004HeadControl::lastOdometryData [private]
 

Definition at line 235 of file GT2004HeadControl.h.

Referenced by setJoints().

RobotPose GT2004HeadControl::lastRobotPose [private]
 

Definition at line 236 of file GT2004HeadControl.h.


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