#include <GT2004HeadControlBasicBehaviors.h>
Inheritance diagram for GT2004BasicBehaviorDirectedScanForLandmarks:
Public Member Functions | |
GT2004BasicBehaviorDirectedScanForLandmarks (Xabsl2ErrorHandler &errorHandler, HeadControlInterfaces &interfaces, GT2004HeadControl &headControl, GT2004HeadPathPlanner &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 110 of file GT2004HeadControlBasicBehaviors.h.
|
Constructor.
Definition at line 114 of file GT2004HeadControlBasicBehaviors.h. References leftOrRight. |
|
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 GT2004HeadControlBasicBehavior. Definition at line 181 of file GT2004HeadControlBasicBehaviors.cpp. References GT2004HeadControl::aimAtLandmark(), Geometry::angleTo(), GT2004HeadControl::calculateClosestLandmark(), CIRCLE, currentLandmark, DEBUG_DRAWING_FINISHED, RobotDimensions::jointLimitHeadPanP, GT2004HeadPathPlanner::lastHeadPan, leftOrRight, nextLandmark, nextLandmarkIsWithinReach, CameraInfo::openingAngleWidth, GT2004HeadControl::setJoints(), waitSomeBeforeLookingAtNextLandmark, and Vector2< V >::y. |
Here is the call graph for this function:
|
Definition at line 120 of file GT2004HeadControlBasicBehaviors.h. Referenced by execute(), and GT2004HeadControlSymbols::getNextLandmarkIsWithinReach(). |
|
Definition at line 123 of file GT2004HeadControlBasicBehaviors.h. Referenced by execute(), and GT2004BasicBehaviorDirectedScanForLandmarks(). |
|
Definition at line 124 of file GT2004HeadControlBasicBehaviors.h. Referenced by execute(). |
|
Definition at line 125 of file GT2004HeadControlBasicBehaviors.h. Referenced by execute(). |
|
Definition at line 126 of file GT2004HeadControlBasicBehaviors.h. Referenced by execute(). |