#include <GT2005HeadControlBasicBehaviors.h>
Inheritance diagram for GT2005BasicBehaviorDirectedScanForLandmarks:


Public Member Functions | |
| GT2005BasicBehaviorDirectedScanForLandmarks (Xabsl2ErrorHandler &errorHandler, HeadControlInterfaces &interfaces, GT2005HeadControl &headControl, GT2005HeadPathPlanner &headPathPlanner, bool &lastScanWasLeft, CameraInfo &cameraInfo) | |
| Constructor. | |
| virtual void | execute () |
| Executes the basic behavior. | |
Public Attributes | |
| bool | nextLandmarkIsWithinReach |
Private Attributes | |
| double | leftOrRight |
| int | currentLandmark |
| int | nextLandmark |
| int | waitSomeBeforeLookingAtNextLandmark |
Definition at line 153 of file GT2005HeadControlBasicBehaviors.h.
|
||||||||||||||||||||||||||||
|
Constructor.
Definition at line 157 of file GT2005HeadControlBasicBehaviors.h. |
|
|
Executes the basic behavior.
alternate scan direction whenever basic behavior is called for the first time The following calculates the closest landmark and compares it to the one that the scan is currently aiming at. If the closest is further in the direction of the scan, it is used as the new target. If it is in the opposite direction, it is not used to guarantee a stable head movement reset variables when a new scan is started if a landmark is found to be closest that is not the one the robot is currently aiming at, store the ID in nextLandmark but don't change the target yet. the following functions as a delay so that the robot continues to look at a landmark for a brief period of time before aiming at the next calculate the XABSL input symbol "nextLandmarkIsWithinReach" Implements GT2005HeadControlBasicBehavior. Definition at line 251 of file GT2005HeadControlBasicBehaviors.cpp. References GT2005HeadControl::aimAtLandmark(), Geometry::angleTo(), GT2005HeadControl::calculateClosestLandmark(), CIRCLE, currentLandmark, DEBUG_DRAWING_FINISHED, RobotDimensions::jointLimitHeadPanP, GT2005HeadPathPlanner::lastHeadPan, nextLandmark, nextLandmarkIsWithinReach, CameraInfo::openingAngleWidth, GT2005HeadControl::setJoints(), waitSomeBeforeLookingAtNextLandmark, and Vector2< V >::y. |
Here is the call graph for this function:

|
|
Definition at line 163 of file GT2005HeadControlBasicBehaviors.h. Referenced by execute(), and GT2005HeadControlSymbols::getNextLandmarkIsWithinReach(). |
|
|
Definition at line 166 of file GT2005HeadControlBasicBehaviors.h. |
|
|
Definition at line 167 of file GT2005HeadControlBasicBehaviors.h. Referenced by execute(). |
|
|
Definition at line 168 of file GT2005HeadControlBasicBehaviors.h. Referenced by execute(). |
|
|
Definition at line 169 of file GT2005HeadControlBasicBehaviors.h. Referenced by execute(). |
1.3.6