#include <GT2005HeadControl.h>
Inheritance diagram for GT2005HeadControl:


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 | |
| GT2005HeadControl (HeadControlInterfaces &interfaces) | |
| Constructor. | |
| ~GT2005HeadControl () | |
| 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 (Pose2D pose, double direction, double nextLeftOrRight, bool disregardFieldMarkings=false) |
| return the closest landmark w.r.t. | |
| int | calculateClosestLandmark (double direction=0, double nextLeftOrRight=0) |
| 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 | |
| GT2005HeadPathPlanner | 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. | |
| GT2005HeadControlSymbols | symbols |
| The symbols used by the Xabsl2Engine. | |
| GT2005HeadControlBasicBehaviors | 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 GT2005HeadControl:: { ... } | calibrationState |
| long | calibrationTime |
| int | calibrationTimeOutsTilt1 |
| int | calibrationTimeOutsPan |
| int | calibrationTimeOutsTilt2 |
| int | calibrationRoundCount |
| int | calibrationSuccessfulRounds |
Private Member Functions | |
| void | showVisualizationQuality () |
Private Attributes | |
| Range< double > | jointRangeNeckTilt |
| Range< double > | jointRangeHeadPan |
| Range< double > | jointRangeHeadTilt |
| OdometryData | lastOdometryData |
| RobotPose | lastRobotPose |
Jan Hoffmann
Uwe Düffert
Martin Lötzsch
Definition at line 31 of file GT2005HeadControl.h.
|
|
The minimum head speed in urad per frame: 4000 = 28.6°/s.
Definition at line 84 of file GT2005HeadControl.h. |
|
|
Definition at line 172 of file GT2005HeadControl.h. |
|
Here is the call graph for this function:

|
|
Destructor.
Definition at line 41 of file GT2005HeadControl.h. |
|
|
Executes the module.
Reimplemented from Module. Definition at line 134 of file GT2005HeadControl.cpp. References SensorData::data, DEBUG_RESPONSE, GTXabsl2EngineExecutor::executeEngine(), RobotState::getButtonDuration(), RobotState::getButtonPressed(), HeadControlMode::headControlMode, headPathPlanner, SensorDataBuffer::lastFrame(), lastHeadControlMode, GT2005HeadPathPlanner::lastHeadPan, GT2005HeadPathPlanner::lastHeadTilt, GT2005HeadPathPlanner::lastNeckTilt, GTXabsl2Profiler::profilerCollectMode, GTXabsl2Profiler::profilerWriteMode, PIDData::setToDefaults(), showVisualizationQuality(), symbols, and GT2005HeadControlSymbols::update(). |
Here is the call graph for this function:

|
|
Is called for every incoming debug message.
Reimplemented from Xabsl2HeadControl. Definition at line 193 of file GT2005HeadControl.cpp. References Xabsl2HeadControl::handleMessage(). |
Here is the call graph for this function:

|
|
Registers symbols and basic behaviors at the engine.
Implements GTXabsl2EngineExecutor. Definition at line 128 of file GT2005HeadControl.cpp. References GT2005HeadControlBasicBehaviors::registerBasicBehaviors(), GT2005HeadControlSymbols::registerSymbols(), and symbols. |
Here is the call graph for this function:

|
|
Is true, if the head is on the left side.
Definition at line 82 of file GT2005HeadControl.cpp. References SensorData::data, and SensorDataBuffer::lastFrame(). |
Here is the call graph for this function:

|
|
put the sensor values in var pos
Definition at line 87 of file GT2005HeadControl.cpp. References SensorData::data, SensorDataBuffer::lastFrame(), Vector3< V >::x, Vector3< V >::y, and Vector3< V >::z. |
Here is the call graph for this function:

|
||||||||||||
|
returns a distance between actual position and comp. the small results are better Definition at line 120 of file GT2005HeadControl.cpp. References SensorData::data, SensorDataBuffer::lastFrame(), and Vector3< V >::y. |
Here is the call graph for this function:

|
||||||||||||||||||||||||
|
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 263 of file GT2005HeadControl.cpp. References Vector2< double >::abs(), Vector2< V >::abs(), direction, headPathPlanner, GT2005HeadPathPlanner::headPositionReached(), jointRangeHeadPan, jointRangeHeadTilt, jointRangeNeckTilt, GT2005HeadPathPlanner::lastHeadPan, GT2005HeadPathPlanner::lastHeadTilt, GT2005HeadPathPlanner::lastNeckTilt, 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 GT2005BasicBehaviorDirectedScanForObstacles::execute(), and GT2005BasicBehaviorDirectedScanForLandmarks::execute(). |
Here is the call graph for this function:

|
||||||||||||||||||||
|
Definition at line 251 of file GT2005HeadControl.cpp. References headPathPlanner, jointRangeHeadPan, jointRangeHeadTilt, jointRangeNeckTilt, GT2005HeadPathPlanner::lastHeadPan, GT2005HeadPathPlanner::lastHeadTilt, GT2005HeadPathPlanner::lastNeckTilt, Range< double >::limit(), HeadMotionRequest::mouth, HeadMotionRequest::pan, HeadMotionRequest::roll, HeadMotionRequest::tilt, and toMicroRad(). |
Here is the call graph for this function:

|
||||||||||||||||||||||||
|
Definition at line 361 of file GT2005HeadControl.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:

|
||||||||||||||||||||||||
|
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 413 of file GT2005HeadControl.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(), beginBallSearchAt(), and GT2005BasicBehaviorDirectedScanForObstacles::execute(). |
Here is the call graph for this function:

|
||||||||||||||||||||
|
Simplified "look at 3d-point" subroutine trying to find tilt1 solution for given tilt2/roll. this is useful on ERS210 and ERS7
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 430 of file GT2005HeadControl.cpp. References RotationMatrix::rotateY(), RotationMatrix::rotateZ(), and Vector3< V >::z. Referenced by simpleLookAtPointRelativeToRobot(). |
Here is the call graph for this function:

|
||||||||||||||||||||||||
|
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. |
|
||||||||||||||||||||||||||||
|
look at 3d-point subroutine trying to find tilt1 solution for given tilt2/roll. this is useful on ERS210 and ERS7
|
|
||||||||||||||||||||||||||||
|
look at 3d-point subroutine trying to find tilt2 solution for given tilt1. this is only useful on ERS7
|
|
||||||||||||||||||||
|
return the closest landmark w.r.t. a given direction; also, the next landmark to the left (or right) can be calculated. a pose can be specified; if it is not specified, the robot pose is used
Definition at line 465 of file GT2005HeadControl.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 calculateClosestLandmark(), and GT2005BasicBehaviorDirectedScanForLandmarks::execute(). |
Here is the call graph for this function:

|
||||||||||||
|
Definition at line 460 of file GT2005HeadControl.cpp. References calculateClosestLandmark(). |
Here is the call graph for this function:

|
||||||||||||||||||||
|
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 322 of file GT2005HeadControl.cpp. References CameraInfo::resolutionHeight, and simpleLookAtPointOnField(). Referenced by GT2005BasicBehaviorDirectedScanForLandmarks::execute(). |
Here is the call graph for this function:

|
||||||||||||||||||||
|
returns the angles that are good for looking at the ball
Definition at line 342 of file GT2005HeadControl.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:

|
|
initial the main angles for the head movement
Definition at line 522 of file GT2005HeadControl.cpp. References headDown, headLeftDown, headMiddleLeft, headMiddleLeftDown, headMiddleRight, headMiddleRightDown, headRightDown, headUp, Vector3< double >::x, Vector3< double >::y, and Vector3< double >::z. Referenced by GT2005HeadControl(). |
|
|
Definition at line 566 of file GT2005HeadControl.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, GT2005HeadPathPlanner::headPathSpeedHeadPan, GT2005HeadPathPlanner::headPathSpeedHeadTilt, GT2005HeadPathPlanner::headPathSpeedNeckTilt, headPositionReached(), headUp, idText, GT2005HeadPathPlanner::init(), GT2005HeadPathPlanner::isLastPathFinished(), isTimedOut(), OUTPUT, speedHeadPan, speedHeadTilt, speedNeckTilt, Vector3< V >::x, Vector3< V >::y, and Vector3< V >::z. |
Here is the call graph for this function:

|
|
Definition at line 195 of file GT2005HeadControl.h. References calibrationState, calibrationStateStart, calibrationTimeOutsPan, calibrationTimeOutsTilt1, and calibrationTimeOutsTilt2. Referenced by GT2005HeadControl(). |
|
|
Definition at line 203 of file GT2005HeadControl.h. References headPathPlanner, and GT2005HeadPathPlanner::headPositionReached(). Referenced by calibrateHeadSpeed(). |
Here is the call graph for this function:

|
|
return the index of the last seen beacon
Definition at line 68 of file GT2005HeadControl.cpp. References LandmarksState::lastSeenBeaconIndex(). Referenced by GT2005HeadControlSymbols::update(). |
Here is the call graph for this function:

|
|
return the time of the last seen beacon
Definition at line 72 of file GT2005HeadControl.cpp. References LandmarksState::timeOfLastSeenBeacon(). Referenced by GT2005HeadControlSymbols::getTimeSinceLastSeenABeacon(). |
Here is the call graph for this function:

|
|
return the time between the two last seen beacons
Definition at line 77 of file GT2005HeadControl.cpp. References LandmarksState::timeBetweenSeen2LastBeacons(). Referenced by GT2005HeadControlSymbols::getTimeBetweenSeen2LastBeacons(). |
Here is the call graph for this function:

|
|
Definition at line 218 of file GT2005HeadControl.h. References calibrationTime, and SystemCall::getTimeSince(). Referenced by calibrateHeadSpeed(). |
Here is the call graph for this function:

|
|
Definition at line 223 of file GT2005HeadControl.h. References calibrationState, and calibrationStateReady. |
|
|
looks to the left/right side an aearch for ball. Used for kicks Definition at line 107 of file GT2005HeadControl.cpp. References headDown, headMiddleLeft, headPathPlanner, GT2005HeadPathPlanner::init(), and lastScanWasLeft. |
Here is the call graph for this function:

|
|
Definition at line 94 of file GT2005HeadControl.cpp. References headDown, headMiddleRight, headPathPlanner, GT2005HeadPathPlanner::init(), and lastScanWasLeft. |
Here is the call graph for this function:

|
|
begin a ball search by the given start position
Definition at line 199 of file GT2005HeadControl.cpp. References headDown, headLeftDown, headMiddleLeft, headMiddleLeftDown, headMiddleRight, headMiddleRightDown, headPathPlanner, headRightDown, headUp, GT2005HeadPathPlanner::init(), lastScanWasLeft, normalize(), Pose2D::rotation, simpleLookAtPointOnField(), Pose2D::translation, Vector2< V >::x, and Vector2< V >::y. |
Here is the call graph for this function:

|
|
Definition at line 174 of file GT2005HeadControl.cpp. References RobotPose::getPositionVariance(), HeadControlMode::headControlMode, MODIFY, and HeadMotionRequest::mouth. Referenced by execute(). |
Here is the call graph for this function:

|
|
An instance of the head path planner.
Definition at line 57 of file GT2005HeadControl.h. Referenced by beginBallSearchAt(), calibrateHeadSpeed(), execute(), GT2005HeadControlSymbols::getLastHeadPathIsFinished(), GT2005HeadControl(), headPositionReached(), searchForBallLeft(), searchForBallRight(), setJoints(), and setJointsDirect(). |
|
|
If true, the last head movement was directed to the left side (of the ball).
Definition at line 60 of file GT2005HeadControl.h. Referenced by beginBallSearchAt(), searchForBallLeft(), and searchForBallRight(). |
|
|
The head control mode that was executed in the last frame.
Definition at line 72 of file GT2005HeadControl.h. Referenced by execute(). |
|
|
Information about the used camera.
Definition at line 75 of file GT2005HeadControl.h. |
|
|
The symbols used by the Xabsl2Engine.
Definition at line 78 of file GT2005HeadControl.h. Referenced by execute(), and registerSymbolsAndBasicBehaviors(). |
|
|
The basic behaviors used by the Xabsl2Engine.
Definition at line 81 of file GT2005HeadControl.h. |
|
|
stores the number of frames "setjoints" has been close to its destination
Definition at line 138 of file GT2005HeadControl.h. Referenced by GT2005HeadControlSymbols::getSetJointsIsCloseToDestination(), and setJoints(). |
|
|
true if the max pan of the head joint is reached
Definition at line 141 of file GT2005HeadControl.h. Referenced by GT2005HeadControlSymbols::getSetJointsMaxPanReached(), and setJoints(). |
|
|
basic headpositions for the gaze
Definition at line 148 of file GT2005HeadControl.h. |
|
|
Definition at line 149 of file GT2005HeadControl.h. |
|
|
Definition at line 150 of file GT2005HeadControl.h. Referenced by beginBallSearchAt(), searchForBallLeft(), and setupMainAngles(). |
|
|
Definition at line 151 of file GT2005HeadControl.h. Referenced by beginBallSearchAt(), and setupMainAngles(). |
|
|
Definition at line 152 of file GT2005HeadControl.h. Referenced by beginBallSearchAt(), searchForBallRight(), and setupMainAngles(). |
|
|
Definition at line 153 of file GT2005HeadControl.h. Referenced by beginBallSearchAt(), and setupMainAngles(). |
|
|
Definition at line 154 of file GT2005HeadControl.h. Referenced by beginBallSearchAt(), and setupMainAngles(). |
|
|
Definition at line 155 of file GT2005HeadControl.h. Referenced by beginBallSearchAt(), and setupMainAngles(). |
|
|
Definition at line 156 of file GT2005HeadControl.h. Referenced by beginBallSearchAt(), calibrateHeadSpeed(), and setupMainAngles(). |
|
|
Definition at line 157 of file GT2005HeadControl.h. Referenced by beginBallSearchAt(), searchForBallLeft(), searchForBallRight(), and setupMainAngles(). |
|
|
speed in rad/s for head movement. its used for headpathplanner and the calibration Definition at line 160 of file GT2005HeadControl.h. Referenced by calibrateHeadSpeed(), and GT2005HeadControl(). |
|
|
Definition at line 161 of file GT2005HeadControl.h. Referenced by calibrateHeadSpeed(), and GT2005HeadControl(). |
|
|
Definition at line 162 of file GT2005HeadControl.h. Referenced by calibrateHeadSpeed(), and GT2005HeadControl(). |
|
|
Definition at line 170 of file GT2005HeadControl.h. Referenced by GT2005HeadControl(). |
|
|
Referenced by calibrateHeadSpeed(), calibrateHeadSpeedIsReady(), and calibrationReset(). |
|
|
Definition at line 191 of file GT2005HeadControl.h. Referenced by calibrateHeadSpeed(), and isTimedOut(). |
|
|
Definition at line 192 of file GT2005HeadControl.h. Referenced by calibrateHeadSpeed(), and calibrationReset(). |
|
|
Definition at line 192 of file GT2005HeadControl.h. Referenced by calibrateHeadSpeed(), and calibrationReset(). |
|
|
Definition at line 192 of file GT2005HeadControl.h. Referenced by calibrateHeadSpeed(), and calibrationReset(). |
|
|
Definition at line 193 of file GT2005HeadControl.h. Referenced by calibrateHeadSpeed(). |
|
|
Definition at line 193 of file GT2005HeadControl.h. Referenced by calibrateHeadSpeed(). |
|
|
Definition at line 237 of file GT2005HeadControl.h. Referenced by GT2005HeadControl(), setJoints(), setJointsDirect(), and simpleLookAtPointRelativeToRobot(). |
|
|
Definition at line 237 of file GT2005HeadControl.h. Referenced by GT2005HeadControl(), setJoints(), setJointsDirect(), and simpleLookAtPointRelativeToRobot(). |
|
|
Definition at line 237 of file GT2005HeadControl.h. Referenced by GT2005HeadControl(), setJoints(), setJointsDirect(), and simpleLookAtPointRelativeToRobot(). |
|
|
Definition at line 240 of file GT2005HeadControl.h. |
|
|
Definition at line 241 of file GT2005HeadControl.h. |
1.3.6