#include <Drive.h>
Public Member Functions | |
bool | initialize () |
void | setStandardSpeed (double speed, double omega) |
void | setPosition (double x, double y, double phi) |
void | getPosition (double &x, double &y, double &phi) |
void | driveWith (double speed, double omega) |
void | drive (double distance) |
void | driveCircle (double radius, double angle) |
bool | driveTo (double x, double y) |
bool | driveTo (double x, double y, double phi) |
void | turnRight (double angle) |
void | turnLeft (double angle) |
void | turnTo (double angle) |
bool | done () |
void | wait () |
bool | stalled () |
double | getRotationAngleTo (double pointX, double pointY) |
double | getRotationAngle (double baseX, double baseY, double pointX, double pointY, double phi) |
void | driveCurveTo (double x, double y) |
void | turn (double angle) |
void | turnLeft () |
void | turnRight () |
void | driveCurve (double distanceOnCurve, double deltaPhi) |
void | stop () |
void | driveStraight () |
void | backup () |
double | distanceTo (double x, double y) |
bool | commandCompleted () |
void | local2global (double robotX, double robotY, double robotPhi, double localX, double localY, double &globalX, double &globalY) |
Static Public Member Functions | |
Drive * | getDrive () |
Protected Member Functions | |
Drive () | |
~Drive () | |
bool | release () |
Private Attributes | |
VWHandle | vwDriveHandle |
double | standardSpeed |
double | standardOmega |
Static Private Attributes | |
Drive | drives [NUMBER_OF_ROBOTS] |
|
|
|
|
|
Makes robot backup with standard speed until a new drive command is issued
|
|
After issuing a new drive command this method can be called to observe its execution. If the drive command is completed successfully true is returned. If the drive stalls during execution the drive is stopped and false is returned
|
|
Calculates the distance from the current robot position to the passed point
|
|
Used to check whether the last driving command has terminated. Attention: if you use any commands that have no termination criterion, e.g. driveWith, driveStraight, backup, ... this method will return false even if the robot is still in motion!
|
|
Lets the robot drive straight the given distance
|
|
Lets the robot drive in circles
|
|
Drives a curve segment of length distanceOnCurve with overall vehicle turn of deltaPhi. standardSpeed is used as driving speed
|
|
Drives to the passed position in a curve. If the angle from the current position to the point is 0 it drives straight if the angle to the point is >= 135 then it turns to the point and drives straight
|
|
Makes robot drive straight with standard speed until a new drive command is issued
|
|
Drives the robot to the indicated point. The robot turns into the direction of the point and drives to the point in a straight line. Then it turns to the demanded angle. This is a blocking call, it returns only after completion of the driving sequence
|
|
Drives the robot to the indicated point. The robot turns into the direction of the point and drives to the point in a straight line. This is a blocking call, it returns only after completion of the driving sequence
|
|
Lets the robot drive with the given speed and omega until a new drive or turn command is given.
|
|
This method is used to get the instance of this singleton class
|
|
Returns the current position of the robot
|
|
Calculates the angle of an vector (base and point), adjusted by an angle phi. Example: if you pass (0.0, 0.0, 1.0, 1.0, 0.0) the vector has an angle of -45.0 degrees in the robot coordinate system. Example: if your robot's current orientation is + 90 degrees you can pass (0.0, 0.0, 1.0, 1.0, 90.0) and you will get -135 as result. So you know you have to turn by -135 to face -45
|
|
Calculates the rotation angle from the current robot position (x,y,phi) to a point. Example: if your robot's current orientation is +0 degrees and you pass (1.0, 1.0) you will get -45 as result. So you know you have to turn by -45 to face (1,1) Example: if your robot's current orientation is + 90 degrees and you pass (1.0, 1.0) you will get -135 as result. So you know you have to turn by -135 to face (1,1)
|
|
Initializes the drive for usage. Should automatically be called by the constructor. But as the EyeSim simulator is not able to execute RoBIOS library functions in class constructors, we have declared this method as public and need to call this method manually in main
|
|
Converts a vector from local coordinates (i.e. relative to a robot position) to global coordinates (i.e. relative to (0,0))
|
|
Releases the drive after usage. Is automatically called by the destructor
|
|
Changes the coordinate system of the robot
|
|
Used to set the standard speed and the standard turning speed that will be used for the driving commands
|
|
Checks whether the robot has hit an object and at least one of the wheels is blocking. Because the stalled information is not always correct when using real robots (for example stalled is true when the robot is just starting up) this method uses an internal counter. Only if a certain threshold is exceeded this method will return true. To reset the counter it is advised to always call Drive::stop if the drive was stalled before
|
|
Stops the robot by setting its speed to (0,0) |
|
Turns robot by the indicated angle (angle>0 means counter-clockwise, angle<0 means clockwise)
|
|
Lets the robot turn counter-clockwise with the standard omega until a new drive or turn command is given |
|
Turns robot left by the indicated angle
|
|
Lets the robot turn clockwise with the standard omega until a new drive or turn command is given |
|
Turns robot right by the indicated angle
|
|
Turns the robot to the indicated angle
|
|
Blocks the calling thread until the robot has finished the current driving command |
|
The single instance that exists of this class
|
|
Stores the standard turning speed that is used for all driving commands (in degree per second) |
|
Stores the standard speed that is used for all driving commands |
|
Used internally to access the robot drive |