#include <ArRobot.h>
Public Types | |
enum | WaitState { WAIT_CONNECTED, WAIT_FAILED_CONN, WAIT_RUN_EXIT, WAIT_TIMEDOUT, WAIT_INTR, WAIT_FAIL } |
Public Methods | |
ArRobot (const char *name=NULL, bool ignored=true, bool doSigHandle=true, bool normalInit=true) | |
Constructor. More... | |
~ArRobot () | |
Destructor. | |
void | run (bool stopRunIfNotConnected) |
Starts the instance to do processing in this thread. More... | |
void | runAsync (bool stopRunIfNotConnected) |
Starts the instance to do processing in its own new thread. More... | |
bool | isRunning (void) const |
Returns whether the robot is currently running or not. More... | |
void | stopRunning (bool doDisconnect=true) |
Stops the robot from doing any more processing. More... | |
void | setDeviceConnection (ArDeviceConnection *connection) |
Sets the connection this instance uses. More... | |
ArDeviceConnection * | getDeviceConnection (void) const |
Gets the connection this instance uses. More... | |
bool | isConnected (void) const |
Questions whether the robot is connected or not. More... | |
bool | blockingConnect (void) |
Connects to a robot, not returning until connection made or failed. More... | |
bool | asyncConnect (void) |
Connects to a robot, from the robots own thread. More... | |
bool | disconnect (void) |
Disconnects from a robot. More... | |
void | clearDirectMotion (void) |
Clears what direct motion commands have been given, so actions work. More... | |
bool | isDirectMotion (void) const |
Returns true if direct motion commands are blocking actions. More... | |
void | enableMotors () |
Enables the motors on the robot. More... | |
void | disableMotors () |
Disables the motors on the robot. More... | |
void | stop (void) |
Stops the robot
| |
void | setVel (double velocity) |
Sets the velocity
| |
void | setVel2 (double leftVelocity, double rightVelocity) |
Sets the velocity of the wheels independently
| |
void | move (double distance) |
Move the given distance forward/backwards
| |
bool | isMoveDone (double delta=0.0) |
Sees if the robot is done moving the previously given move. More... | |
void | setMoveDoneDist (double dist) |
Sets the difference required for being done with a move. | |
double | getMoveDoneDist (void) |
Gets the difference required for being done with a move. | |
void | setHeading (double heading) |
Sets the heading
| |
void | setRotVel (double velocity) |
Sets the rotational velocity
| |
void | setDeltaHeading (double deltaHeading) |
Sets the delta heading
| |
bool | isHeadingDone (double delta=0.0) const |
Sees if the robot is done changing to the previously given setHeading. More... | |
void | setHeadingDoneDiff (double degrees) |
sets the difference required for being done with a heading change. | |
double | getHeadingDoneDiff (void) const |
Gets the difference required for being done with a heading change. | |
void | setDirectMotionPrecedenceTime (int mSec) |
Sets the length of time a direct motion command will take precedence over actions, in milliseconds. More... | |
unsigned int | getDirectMotionPrecedenceTime (void) const |
Gets the length of time a direct motion command will take precedence over actions, in milliseconds. More... | |
bool | com (unsigned char command) |
Sends a command to the robot with no arguments. More... | |
bool | comInt (unsigned char command, short int argument) |
Sends a command to the robot with an int for argument. More... | |
bool | com2Bytes (unsigned char command, char high, char low) |
Sends a command to the robot with two bytes for argument. More... | |
bool | comStr (unsigned char command, const char *argument) |
Sends a command to the robot with a string for argument. More... | |
bool | comStrN (unsigned char command, const char *str, int size) |
Sends a command to the robot with a size bytes of str as argument. More... | |
const char * | getRobotName (void) const |
Returns the Robot's name that is set in its onboard configuration. | |
const char * | getRobotType (void) const |
Returns the type of the robot connected to. | |
const char * | getRobotSubType (void) const |
Returns the subtype of the robot connected to. | |
double | getAbsoluteMaxTransVel (void) const |
Gets the robots absolute maximum translational velocity. | |
bool | setAbsoluteMaxTransVel (double maxVel) |
Sets the robots absolute maximum translational velocity. More... | |
double | getAbsoluteMaxRotVel (void) const |
Gets the robots absolute maximum rotational velocity. | |
bool | setAbsoluteMaxRotVel (double maxVel) |
Sets the robots absolute maximum rotational velocity. More... | |
ArPose | getPose (void) const |
Gets the global position of the robot. | |
double | getX (void) const |
Gets the global X location of the robot. | |
double | getY (void) const |
Gets the global Y location of the robot. | |
double | getTh (void) const |
Gets the global Th location of the robot. | |
double | findDistanceTo (const ArPose pose) |
Gets the distance to a point from the robot. | |
double | findAngleTo (const ArPose pose) |
Gets the distance to a point from the robot. | |
double | findDeltaHeadingTo (const ArPose pose) |
Gets the distance to a point from the robot. | |
double | getVel (void) const |
Gets the translational velocity of the robot. | |
double | getRotVel (void) const |
Gets the rotational velocity of the robot. | |
double | getRobotRadius (void) const |
Gets the robot radius (in mm). | |
double | getRobotDiagonal (void) const |
Gets the robot diagonal (half-height to diagonal of octagon) (in mm). | |
double | getBatteryVoltage (void) const |
Gets the battery voltage of the robot. More... | |
double | getBatteryVoltageNow (void) const |
Gets the instaneous battery voltage. | |
double | getLeftVel (void) const |
Gets the velocity of the left wheel. | |
double | getRightVel (void) const |
Gets the velocity of the right wheel. | |
int | getStallValue (void) const |
Gets the 2 bytes of stall return from the robot. | |
bool | isLeftMotorStalled (void) const |
Returns true if the left motor is stalled. | |
bool | isRightMotorStalled (void) const |
Returns true if the left motor is stalled. | |
double | getControl (void) const |
Gets the control heading. More... | |
int | getFlags (void) const |
Gets the flags values. | |
bool | areMotorsEnabled (void) const |
returns true if the motors are enabled. | |
bool | areSonarsEnabled (void) const |
returns true if the motors are enabled. | |
double | getCompass (void) const |
Gets the compass heading from the robot. | |
int | getAnalogPortSelected (void) const |
Gets which analog port is selected. | |
unsigned char | getAnalog (void) const |
Gets the analog value. | |
unsigned char | getDigIn (void) const |
Gets the byte representing digital input status. | |
unsigned char | getDigOut (void) const |
Gets the byte representing digital output status. | |
int | getIOAnalogSize (void) const |
Gets the number of bytes in the analog IO buffer. | |
int | getIODigInSize (void) const |
Gets the number of bytes in the digital input IO buffer. | |
int | getIODigOutSize (void) const |
Gets the number of bytes in the digital output IO buffer. | |
int | getIOAnalog (int num) const |
Gets the n'th byte from the analog input data from the IO packet. More... | |
double | getIOAnalogVoltage (int num) const |
Gets the n'th byte from the analog input data from the IO packet. More... | |
unsigned char | getIODigIn (int num) const |
Gets the n'th byte from the digital input data from the IO packet. | |
unsigned char | getIODigOut (int num) const |
Gets the n'th byte from the digital output data from the IO packet. | |
bool | hasTableSensingIR (void) const |
Gets whether the robot has table sensing IR or not (see params in docs). | |
bool | isLeftTableSensingIRTriggered (void) const |
Returns true if the left table sensing IR is triggered. | |
bool | isRightTableSensingIRTriggered (void) const |
Returns true if the right table sensing IR is triggered. | |
bool | isLeftBreakBeamTriggered (void) const |
Returns true if the left break beam IR is triggered. | |
bool | isRightBreakBeamTriggered (void) const |
Returns true if the right break beam IR is triggered. | |
ArTime | getIOPacketTime (void) const |
Returns the time received of the last IO packet. | |
bool | getEstop (void) |
Returns true if the E-Stop button is pressed. | |
bool | hasFrontBumpers (void) const |
Gets whether the robot has front bumpers (see params in docs). | |
unsigned int | getNumFrontBumpers (void) const |
Gets the number of the front bumpers. | |
bool | hasRearBumpers (void) const |
Gets whether the robot has rear bumpers (see params in docs). | |
unsigned int | getNumRearBumpers (void) const |
Gets the number of the rear bumpers. | |
ArPose | getEncoderPose (void) const |
Gets the position of the robot according to the encoders. | |
int | getMotorPacCount (void) const |
Gets the number of motor packets received in the last second. | |
int | getSonarPacCount (void) const |
Gets the number of sonar returns received in the last second. | |
int | getSonarRange (int num) const |
Gets the range of the last sonar reading for the given sonar. More... | |
bool | isSonarNew (int num) const |
Find out if the given sonar has a new reading. More... | |
int | getNumSonar (void) const |
Find the number of sonar there are. | |
ArSensorReading * | getSonarReading (int num) const |
Returns the sonar reading for the given sonar. More... | |
int | getClosestSonarRange (double startAngle, double endAngle) const |
Returns the closest of the current sonar reading in the given range. | |
int | getClosestSonarNumber (double startAngle, double endAngle) const |
Returns the number of the sonar that has the closest current reading in the given range. | |
const char * | getName (void) const |
Gets the robots name in ARIAs list. | |
void | setName (const char *name) |
Sets the robots name in ARIAs list. | |
void | moveTo (ArPose pose, bool doCumulative=true) |
Moves the robot's idea of its position to this position. More... | |
void | moveTo (ArPose to, ArPose from, bool doCumulative=true) |
Moves the robot's RW position to reflect pose From => pose To. More... | |
size_t | getBatteryVoltageAverageOfNum (void) |
Gets the number of readings the battery voltage is the average of. | |
void | setBatteryVoltageAverageOfNum (size_t numToAverage) |
Sets the number of readings the battery voltage is the average of (default 20). | |
void | requestEncoderPackets (void) |
Starts a continuous stream of encoder packets. | |
void | requestIOPackets (void) |
Starts a continuous stream of IO packets. | |
void | stopEncoderPackets (void) |
Stops a continuous stream of encoder packets. | |
void | stopIOPackets (void) |
Stops a continuous stream of IO packets. | |
long int | getLeftEncoder (void) |
Gets packet data from the left encoder. | |
long int | getRightEncoder (void) |
Gets packet data from the right encoder. | |
void | setEncoderTransform (ArPose deadReconPos, ArPose globalPos) |
Changes the transform. More... | |
void | setEncoderTransform (ArPose transformPos) |
Changes the transform directly. More... | |
ArTransform | getEncoderTransform (void) const |
Gets the encoder transform. More... | |
ArTransform | getToGlobalTransform (void) const |
This gets the transform from local coords to global coords. More... | |
ArTransform | getToLocalTransform (void) const |
This gets the transform for going from global coords to local coords. More... | |
void | applyTransform (ArTransform trans, bool doCumulative=true) |
This applies a transform to all the robot range devices and to the sonar. More... | |
void | setDeadReconPose (ArPose pose) |
Sets the dead recon position of the robot. More... | |
void | addRangeDevice (ArRangeDevice *device) |
Adds a rangeDevice to the robot's list of them, and set the device's robot pointer. | |
void | remRangeDevice (const char *name) |
Remove a range device from the robot's list, by name. More... | |
void | remRangeDevice (ArRangeDevice *device) |
Remove a range device from the robot's list, by instance. More... | |
const ArRangeDevice * | findRangeDevice (const char *name) const |
Finds a rangeDevice in the robot's list. More... | |
ArRangeDevice * | findRangeDevice (const char *name) |
Finds a rangeDevice in the robot's list. More... | |
std::list< ArRangeDevice *> * | getRangeDeviceList (void) |
Gets the range device list. More... | |
bool | hasRangeDevice (ArRangeDevice *device) const |
Finds whether a particular range device is attached to this robot or not. More... | |
double | checkRangeDevicesCurrentPolar (double startAngle, double endAngle, double *angle=NULL) const |
Goes through all the range devices and checks them. More... | |
double | checkRangeDevicesCumulativePolar (double startAngle, double endAngle, double *angle=NULL) const |
Goes through all the range devices and checks them. More... | |
double | checkRangeDevicesCurrentBox (double x1, double y1, double x2, double y2, ArPose *readingPos=NULL) const |
double | checkRangeDevicesCumulativeBox (double x1, double y1, double x2, double y2, ArPose *readingPos=NULL) const |
void | setPTZ (ArPTZ *ptz) |
Sets the camera this robot is using. | |
ArPTZ * | getPTZ (void) |
Sets the camera this robot is using. | |
void | setStateReflectionRefreshTime (int msec) |
Sets the number of milliseconds between state reflection refreshes if the state has not changed. More... | |
int | getStateReflectionRefreshTime (void) const |
Sets the number of milliseconds between state reflection refreshes if the state has not changed. More... | |
void | addPacketHandler (ArRetFunctor1< bool, ArRobotPacket *> *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a packet handler to the list of packet handlers. More... | |
void | remPacketHandler (ArRetFunctor1< bool, ArRobotPacket *> *functor) |
Removes a packet handler from the list of packet handlers. More... | |
void | addConnectCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a connect callback. More... | |
void | remConnectCB (ArFunctor *functor) |
Adds a disconnect callback. More... | |
void | addFailedConnectCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a callback for when a connection to the robot is failed. More... | |
void | remFailedConnectCB (ArFunctor *functor) |
Removes a callback for when a connection to the robot is failed. More... | |
void | addDisconnectNormallyCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a callback for when disconnect is called while connected. More... | |
void | remDisconnectNormallyCB (ArFunctor *functor) |
Removes a callback for when disconnect is called while connected. More... | |
void | addDisconnectOnErrorCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a callback for when disconnection happens because of an error. More... | |
void | remDisconnectOnErrorCB (ArFunctor *functor) |
Removes a callback for when disconnection happens because of an error. More... | |
void | addRunExitCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a callback for when the run loop exits for what ever reason. More... | |
void | remRunExitCB (ArFunctor *functor) |
Removes a callback for when the run loop exits for what ever reason. More... | |
WaitState | waitForConnect (unsigned int msecs=0) |
Suspend calling thread until the ArRobot is connected. More... | |
WaitState | waitForConnectOrConnFail (unsigned int msecs=0) |
Suspend calling thread until the ArRobot is connected or fails to connect. More... | |
WaitState | waitForRunExit (unsigned int msecs=0) |
Suspend calling thread until the ArRobot run loop has exited. More... | |
void | wakeAllWaitingThreads () |
Wake up all threads waiting on this robot. More... | |
void | wakeAllConnWaitingThreads () |
Wake up all threads waiting for connection. More... | |
void | wakeAllConnOrFailWaitingThreads () |
Wake up all threads waiting for connection or connection failure. More... | |
void | wakeAllRunExitWaitingThreads () |
Wake up all threads waiting for the run loop to exit. More... | |
bool | addUserTask (const char *name, int position, ArFunctor *functor, ArTaskState::State *state=NULL) |
Adds a user task to the list of synchronous taskes. More... | |
void | remUserTask (const char *name) |
Removes a user task from the list of synchronous taskes by name. More... | |
void | remUserTask (ArFunctor *functor) |
Removes a user task from the list of synchronous taskes by functor. More... | |
ArSyncTask * | findUserTask (const char *name) |
Finds a user task by name. More... | |
ArSyncTask * | findUserTask (ArFunctor *functor) |
Finds a user task by functor. More... | |
void | logUserTasks (void) const |
Logs the list of user tasks, strictly for your viewing pleasure. More... | |
void | logAllTasks (void) const |
Logs the list of all tasks, strictly for your viewing pleasure. More... | |
bool | addSensorInterpTask (const char *name, int position, ArFunctor *functor, ArTaskState::State *state=NULL) |
Adds a task under the sensor interp part of the syncronous tasks. More... | |
void | remSensorInterpTask (const char *name) |
Removes a sensor interp tasks by name. More... | |
void | remSensorInterpTask (ArFunctor *functor) |
Removes a sensor interp tasks by functor. More... | |
ArSyncTask * | findTask (const char *name) |
Finds a task by name. More... | |
ArSyncTask * | findTask (ArFunctor *functor) |
Finds a task by functor. More... | |
bool | addAction (ArAction *action, int priority) |
Adds an action to the list with the given priority. More... | |
bool | remAction (ArAction *action) |
Removes an action from the list, by pointer. More... | |
bool | remAction (const char *actionName) |
Removes an action from the list, by name. More... | |
ArAction * | findAction (const char *actionName) |
Returns the first (highest priority) action with the given name (or NULL). More... | |
ArResolver::ActionMap * | getActionMap (void) |
Returns the map of actions... don't do this unless you really know what you're doing. More... | |
void | deactivateActions (void) |
Deactivates all the actions. | |
void | logActions (void) const |
Logs out the actions and their priorities. | |
ArResolver * | getResolver (void) |
Gets the resolver the robot is using. | |
void | setResolver (ArResolver *resolver) |
Sets the resolver the robot is using. | |
void | setEncoderCorrectionCallback (ArRetFunctor1< double, ArPoseWithTime > *functor) |
Sets the encoderCorrectionCallback. More... | |
ArRetFunctor1< double, ArPoseWithTime > * | getEncoderCorrectionCallback (void) const |
Gets the encoderCorrectionCallback. More... | |
void | setCycleTime (unsigned int ms) |
Sets the number of ms between cycles. More... | |
unsigned int | getCycleTime (void) const |
Gets the number of ms between cycles. More... | |
void | setCycleWarningTime (unsigned int ms) |
Sets the number of ms between cycles to warn over. More... | |
unsigned int | getCycleWarningTime (void) const |
Gets the number of ms between cycles to warn over. More... | |
unsigned int | getCycleWarningTime (void) |
Gets the number of ms between cycles to warn over. More... | |
void | setConnectionCycleMultiplier (unsigned int multiplier) |
Sets the multiplier for how many cycles ArRobot waits when connecting. More... | |
unsigned int | getConnectionCycleMultiplier (void) const |
Gets the multiplier for how many cycles ArRobot waits when connecting. More... | |
void | setCycleChained (bool cycleChained) |
Sets whether to chain the robot cycle to when we get in SIP packets. | |
bool | isCycleChained (void) const |
Gets whether we chain the robot cycle to when we get in SIP packets. | |
void | setConnectionTimeoutTime (int mSecs) |
Sets the time without a response until connection assumed lost. More... | |
int | getConnectionTimeoutTime (void) const |
Gets the time without a response until connection assumed lost. More... | |
ArTime | getLastPacketTime (void) const |
Gets the time the last packet was received. More... | |
void | setPoseInterpNumReadings (size_t numReadings) |
Sets the number of packets back in time the ArInterpolation goes. | |
size_t | getPoseInterpNumReadings (void) const |
Sets the number of packets back in time the position interpol goes. | |
int | getPoseInterpPosition (ArTime timeStamp, ArPose *position) |
Gets the position the robot was at at the given timestamp. More... | |
unsigned int | getCounter (void) const |
Gets the Counter for the time through the loop. | |
const ArRobotParams * | getRobotParams (void) const |
Gets the parameters the robot is using. More... | |
const ArRobotConfigPacketReader * | getOrigRobotConfig (void) const |
Gets the original robot config packet information. More... | |
void | setTransVelMax (double vel) |
Sets the maximum translational velocity. | |
void | setTransAccel (double acc) |
Sets the translational acceleration. | |
void | setTransDecel (double decel) |
Sets the translational acceleration. | |
void | setRotVelMax (double vel) |
Sets the maximum rotational velocity. | |
void | setRotAccel (double acc) |
Sets the rotational acceleration. | |
void | setRotDecel (double decel) |
Sets the rotational acceleration. | |
bool | hasSettableVelMaxes (void) const |
If the robot has settable maximum velocities. | |
double | getTransVelMax (void) const |
Gets the maximum translational velocity. | |
double | getRotVelMax (void) const |
Gets the maximum rotational velocity. | |
bool | hasSettableAccsDecs (void) const |
If the robot has settable accels and decels. | |
double | getTransAccel (void) const |
Gets the translational acceleration. | |
double | getTransDecel (void) const |
Gets the translational acceleration. | |
double | getRotAccel (void) const |
Gets the rotational acceleration. | |
double | getRotDecel (void) const |
Gets the rotational acceleration. | |
bool | loadParamFile (const char *file) |
Loads a parameter file (replacing all other params). More... | |
void | attachKeyHandler (ArKeyHandler *keyHandler, bool exitOnEscape=true) |
Attachs a key handler. More... | |
ArKeyHandler * | getKeyHandler (void) const |
Gets the key handler attached to this robot. | |
int | lock () |
Lock the robot instance. | |
int | tryLock () |
Try to lock the robot instance without blocking. | |
int | unlock () |
Unlock the robot instance. | |
bool | isStabilizing (void) |
This tells us if we're in the preconnection state. | |
void | setStabilizingTime (int mSecs) |
How long we should stabilize for in ms (0 disables stabilizing). More... | |
int | getStabilizingTime (void) const |
How long we stabilize for in ms (0 means no stabilizng). More... | |
void | addStabilizingCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a callback called when the robot starts stabilizing before declaring connection. More... | |
void | remStabilizingCB (ArFunctor *functor) |
Removes stabilizing callback. More... | |
ArSyncTask * | getSyncTaskRoot (void) |
This gets the root of the syncronous task tree, only serious developers should use it. More... | |
void | loopOnce (void) |
This function loops once... only serious developers should use it. More... | |
void | incCounter (void) |
This is only for use by syncLoop. | |
void | packetHandler (void) |
Packet Handler, internal. More... | |
void | actionHandler (void) |
Action Handler, internal. More... | |
void | stateReflector (void) |
State Reflector, internal. More... | |
void | robotLocker (void) |
Robot locker, internal. More... | |
void | robotUnlocker (void) |
Robot unlocker, internal. More... | |
void | keyHandlerExit (void) |
For the key handler, escape calls this to exit, internal. | |
bool | processMotorPacket (ArRobotPacket *packet) |
Processes a motor packet, internal. | |
void | processNewSonar (char number, int range, ArTime timeReceived) |
Processes a new sonar reading, internal. | |
bool | processEncoderPacket (ArRobotPacket *packet) |
Processes a new encoder packet, internal. | |
bool | processIOPacket (ArRobotPacket *packet) |
Processes a new IO packet, internal. | |
void | init (void) |
Internal function, shouldn't be used. More... | |
void | setUpSyncList (void) |
Internal function, shouldn't be used, sets up the default sync list. | |
void | setUpPacketHandlers (void) |
Internal function, shouldn't be used, sets up the default packet handlers. | |
int | asyncConnectHandler (bool tryHarderToConnect) |
Internal function, shouldn't be used, does a single run of connecting. More... | |
void | dropConnection (void) |
Internal function, shouldn't be used, drops the conn because of error. | |
void | failedConnect (void) |
Internal function, shouldn't be used, denotes the conn failed. | |
void | madeConnection (void) |
Internal function, shouldn't be used, does the initial conn stuff. | |
void | startStabilization (void) |
Internal function, shouldn't be used, calls the preconnected stuff. | |
void | finishedConnection (void) |
Internal function, shouldn't be used, does the after conn stuff. | |
bool | handlePacket (ArRobotPacket *packet) |
Internal function, takes a packet and passes it to the packet handlers, returns true if handled, false otherwise. | |
std::list< ArFunctor *> * | getRunExitListCopy () |
Internal function, shouldn't be used, does what its name says. | |
void | processParamFile (void) |
Internal function, processes a parameter file. | |
ArPose | getRawEncoderPose (void) const |
Internal function to get the raw encoder reading, don't use it. | |
bool | getNoTimeWarningThisCycle (void) |
Internal function for sync loop and sync task to see if we should warn this cycle or not. | |
void | setNoTimeWarningThisCycle (bool noTimeWarningThisCycle) |
Internal function for sync loop and sync task to say if we should warn this cycle or not. |
This is the most important class, the only classes most people will ever have to use are this one, and the ArSimpleConnector. NOTE: In Windows you cannot make an ArRobot a global, it will crash because the windows compiler initializes the constructors in the wrong order... you can make a pointer to an ArRobot and then new one however.
|
|
|
Constructor.
|
|
Action Handler, internal. Runs the resolver on the actions, it just saves these values for use by the stateReflector, otherwise it sends these values straight down to the robot. |
|
Adds an action to the list with the given priority. Adds an action to the list of actions at the given priority, in the case of two (or more) actions with the same priority, the default resolver (ArPriorityResolver) averages the the multiple readings... the priority can be any integer, but as a convention 0 to 100 is used, with 100 being the highest priority.
|
|
Adds a connect callback. Adds a connect callback, which is an ArFunctor, created as an ArFunctorC. The entire list of connect callbacks is called when a connection is made with the robot. If you have some sort of module that adds a callback, that module must remove the callback when the module is removed.
|
|
Adds a callback for when disconnect is called while connected. Adds a disconnect normally callback,which is an ArFunctor, created as an ArFunctorC. This whole list of disconnect normally callbacks is called when something calls disconnect if the instance isConnected. If there is no connection and disconnect is called nothing is done. If you have some sort of module that adds a callback, that module must remove the callback when the module is removed.
|
|
Adds a callback for when disconnection happens because of an error. Adds a disconnect on error callback, which is an ArFunctor, created as an ArFunctorC. This whole list of disconnect on error callbacks is called when ARIA loses connection to a robot because of an error. This can occur if the physical connection (ie serial cable) between the robot and the computer is severed/disconnected, if one of a pair of radio modems that connect the robot and computer are disconnected, if someone presses the reset button on the robot, or if the simulator is closed while ARIA is connected to it. Note that if the link between the two is lost the ARIA assumes it is temporary until it reaches a timeout value set with setConnectionTimeoutTime. If you have some sort of module that adds a callback, that module must remove the callback when the module removed.
|
|
Adds a callback for when a connection to the robot is failed. Adds a failed connect callback,which is an ArFunctor, created as an ArFunctorC. This whole list of failed connect callbacks is called when an attempt is made to connect to the robot, but fails. The usual reason for this failure is either that there is no robot/sim where the connection was tried to be made, the robot wasn't given a connection, or the radio modems that communicate with the robot aren't on. If you have some sort of module that adds a callback, that module must remove the callback when the module removed.
|
|
Adds a packet handler to the list of packet handlers. Adds a packet handler. A packet handler is an ArRetFunctor1, created as an instance of ArRetFunctor1C. The return is a boolean, while the functor takes an ArRobotPacket pointer as the argument. This functor is placed in the list of functors to call when a packet arrives. This list is gone through by order until one of the handlers returns true. @argument functor the functor to call when the packet comes in @argument position whether to place the functor first or last
|
|
Adds a callback for when the run loop exits for what ever reason. Adds a callback that is called when the run loop exits. The functor is which is an ArFunctor, created as an ArFunctorC. The whole list of functors is called when the run loop exits. This is most usefull for threaded programs that run the robot using ArRobot::runAsync. This will allow user threads to know when the robot loop has exited.
|
|
Adds a task under the sensor interp part of the syncronous tasks. The synchronous tasks get called every robot cycle (every 100 ms by default).
|
|
Adds a callback called when the robot starts stabilizing before declaring connection. Adds a stablizing callback, which is an ArFunctor, created as an ArFunctorC. The entire list of connect callbacks is called just before the connection is called done to the robot. This time can be used to calibtrate readings (on things like gyros).
|
|
Adds a user task to the list of synchronous taskes. The synchronous tasks get called every robot cycle (every 100 ms by default).
|
|
This applies a transform to all the robot range devices and to the sonar. Applies a transform to the range devices... this is mostly useful for translating to/from local/global coords, but may have other uses
|
|
Connects to a robot, from the robots own thread. Sets up the robot to connect, then returns, but the robot must be running (ie from runAsync) before you do this. Also this will fail if the robot is already connected. If you want to know what happened because of the connect then look at the callbacks. NOTE, this will not lock robot before setting values, so you MUST lock the robot before you call this function and unlock the robot after you call this function. If you fail to lock the robot, you'll may wind up with wierd behavior. Other than the aspect of blocking or not the only difference between async and blocking connects (other than the blocking) is that async is run every robot cycle, whereas blocking runs as fast as it can... also blocking will try to reconnect a radio modem if it looks like it didn't get connected in the first place, so blocking can wind up taking 10 or 12 seconds to decide it can't connect, whereas async doesn't try hard at all to reconnect the radio modem (beyond its first try) (under the assumptio! n the async connect is user driven, so they'll just try again, and so that it won't mess up the sync loop by blocking for so long).
|
|
Internal function, shouldn't be used, does a single run of connecting. This is an internal function that is used both for async connects and blocking connects use to connect. It does about the same thing for both, and it should only be used by asyncConnect and blockingConnect really. But here it is. The only difference between when its being used by blocking/async connect is that in blocking mode if it thinks there may be problems with the radio modem it pauses for two seconds trying to deal with this... whereas in async mode it tries to deal with this in a simpler way.
|
|
Attachs a key handler. This will attach a key handler to a robot, by putting it into the robots sensor interp task list (a keyboards a sensor of users will, right?). By default exitOnEscape is true, which will cause this function to add an escape key handler to the key handler, this will make the program exit when escape is pressed... if you don't like this you can pass exitOnEscape in as false.
|
|
Connects to a robot, not returning until connection made or failed. Connects to the robot, returning only when a connection has been made or it has been established a connection can't be made. This connection usually is fast, but can take up to 30 seconds if the robot is in a wierd state (this is not often). If the robot is connected via ArSerialConnection then the connect will also connect the radio modems. Upon a successful connection all of the Connection Callback Functors that have been registered will be called. NOTE, this will lock the robot before setting values, so you MUST not have the robot locked from where you call this function. If you do, you'll wind up in a deadlock. This behavior is there because otherwise you'd have to lock the robot before calling this function, and normally blockingConnect will be called from a seperate thread, and that thread won't be doing anything else with the robot at that time. Other than the aspect of blocking or not the only difference between a! sync and blocking connects (other than the blocking) is that async is run every robot cycle, whereas blocking runs as fast as it can... also blocking will try to reconnect a radio modem if it looks like it didn't get connected in the first place, so blocking can wind up taking 10 or 12 seconds to decide it can't connect, whereas async doesn't try hard at all to reconnect the radio modem (under the assumption the async connect is user driven, so they'll just try again, and so that it won't mess up the sync loop by blocking for so long).
|
|
This goes through all of the registered range devices and locks each, calls cumulativeReadingBox on it, and then unlocks it. Gets the closest reading in a region defined by the two points of a rectangle.
|
|
Goes through all the range devices and checks them. This goes through all of the registered range devices and locks each, calls cumulativeReadingPolar on it, and then unlocks it. Gets the closest reading in a region defined by startAngle going to endAngle... going counterclockwise (neg degrees to poseitive... with how the robot is set up, thats counterclockwise)... from -180 to 180... this means if you want the slice between 0 and 10 degrees, you must enter it as 0, 10, if you do 10, 0 you'll get the 350 degrees between 10 and 0... be especially careful with negative... for example -30 to -60 is everything from -30, around through 0, 90, and 180 back to -60... since -60 is actually to clockwise of -30
|
|
This goes through all of the registered range devices and locks each, calls currentReadingBox on it, and then unlocks it. Gets the closest reading in a region defined by the two points of a rectangle.
|
|
Goes through all the range devices and checks them. This goes through all of the registered range devices and locks each, calls currentReadingPolar on it, and then unlocks it. Gets the closest reading in a region defined by startAngle going to endAngle... going counterclockwise (neg degrees to poseitive... with how the robot is set up, thats counterclockwise)... from -180 to 180... this means if you want the slice between 0 and 10 degrees, you must enter it as 0, 10, if you do 10, 0 you'll get the 350 degrees between 10 and 0... be especially careful with negative... for example -30 to -60 is everything from -30, around through 0, 90, and 180 back to -60... since -60 is actually to clockwise of -30
|
|
Clears what direct motion commands have been given, so actions work. This clears the direct motion commands so that actions will be allowed to control the robot again. |
|
Sends a command to the robot with no arguments.
|
|
Sends a command to the robot with two bytes for argument.
|
|
Sends a command to the robot with an int for argument.
|
|
Sends a command to the robot with a string for argument.
|
|
Sends a command to the robot with a size bytes of str as argument.
|
|
Disables the motors on the robot. This command disables the motors on the robot, if it is connected. |
|
Disconnects from a robot. Disconnects from a robot. This also calls of the DisconnectNormally Callback Functors if the robot was actually connected to a robot when this member was called.
|
|
Enables the motors on the robot. This command enables the motors on the robot, if it is connected. |
|
Returns the first (highest priority) action with the given name (or NULL). Finds the action with the given name... if more than one action has that name it find the one with the highest priority
|
|
Finds a rangeDevice in the robot's list.
|
|
Finds a rangeDevice in the robot's list.
|
|
Finds a task by functor. Finds a task by its functor, searching the entire space of tasks
|
|
Finds a task by name. Finds a task by its name, searching the entire space of tasks
|
|
Finds a user task by functor. Finds a user task by its functor, searching the entire space of tasks
|
|
Finds a user task by name. Finds a user task by its name, searching the entire space of tasks
|
|
Returns the map of actions... don't do this unless you really know what you're doing. This returns the actionMap the robot has... do not mess with this list except by using ArRobot::addAction and ArRobot::remAction... This is jsut for the things like ArActionGroup that want to deactivate or activate all the actions (well, only deactivating everything makes sense).
|
|
Gets the battery voltage of the robot. This value is averaged over a number of readings, you can get this by calling getBatteryVoltageAverageOfNum and set this with setBatteryVoltageAverageOfNum... you can call getBatteryVoltageNow to get the reading from the last packet. |
|
Gets the multiplier for how many cycles ArRobot waits when connecting.
|
|
Gets the time without a response until connection assumed lost. Gets the number of seconds to go without response from the robot until it is assumed tha tthe connection with the robot has been broken and the disconnect on error events will happen. |
|
Gets the control heading. Gets the control heading as an offset from the current heading.
|
|
Gets the number of ms between cycles. Finds the number of milliseconds between cycles, at each cycle is when all packets are processed, all sensors are interpretted, all actions are called, and all user tasks are serviced. Be warned, if you set this too small you could overflow your serial connection.
|
|
Gets the number of ms between cycles to warn over. Sets a time such that if the number of milliseconds between cycles goes over this then there will be an ArLog::log(ArLog::Normal) warning.
|
|
Gets the number of ms between cycles to warn over. Sets a time such that if the number of milliseconds between cycles goes over this then there will be an ArLog::log(ArLog::Normal) warning.
|
|
Gets the connection this instance uses. Gets the connection this instance uses to the actual robot. This is where commands will be sent and packets will be received from
|
|
Gets the length of time a direct motion command will take precedence over actions, in milliseconds. The direct motion precedence time determines how long actions will be ignored after a direct motion command is given. If the direct motion precedence time is 0, then direct motion will take precedence over actions until a clearDirectMotion command is issued. This value defaults to 0.
|
|
Gets the encoderCorrectionCallback. This gets the encoderCorrectionCB, see setEncoderCorrectionCallback for details.
|
|
Gets the encoder transform.
|
|
Gets the n'th byte from the analog input data from the IO packet. This gets the raw IO Analog value, which is a number between 0 and 1024 (2^10). |
|
Gets the n'th byte from the analog input data from the IO packet. This gets the IO Analog value converted to a voltage between 0 and 5 voltes. |
|
Gets the time the last packet was received. This gets the ArTime that the last packet was received at
|
|
Gets the original robot config packet information.
|
|
Gets the position the robot was at at the given timestamp.
|
|
Gets the range device list. This gets the list of range devices attached to this robot, do NOT manipulate this list directly. If you want to manipulate use the appropriate addRangeDevice, or remRangeDevice
|
|
Gets the parameters the robot is using.
|
|
Gets the range of the last sonar reading for the given sonar.
|
|
Returns the sonar reading for the given sonar.
|
|
How long we stabilize for in ms (0 means no stabilizng). This is the amount of time the robot will stabilize for after it has connected to the robot (it won't report it is connected until after this time is over). |
|
Sets the number of milliseconds between state reflection refreshes if the state has not changed. The state reflection refresh time is the number of milliseconds between when the state reflector will refresh the robot, if the command hasn't changed. The default is 500 milliseconds. If this number is less than the cyle time, it'll simply happen every cycle.
|
|
This gets the root of the syncronous task tree, only serious developers should use it. This gets the root of the synchronous task tree, so that someone can add their own new types of tasks, or find out more information about each task... only serious developers should use this.
|
|
This gets the transform from local coords to global coords.
|
|
This gets the transform for going from global coords to local coords.
|
|
Finds whether a particular range device is attached to this robot or not.
|
|
Internal function, shouldn't be used. Sets up the packet handlers, sets up the sync list and makes the default priority resolver. |
|
Questions whether the robot is connected or not.
|
|
Returns true if direct motion commands are blocking actions. Returns the state of direct motion commands: whether actions are allowed or not
|
|
Sees if the robot is done changing to the previously given setHeading. Determines if a setHeading command is finished, to within a small distance. If delta = 0 (default), the delta distance is what was set with setHeadingDoneDiff, you can get the distnace with getHeadingDoneDiff
|
|
Sees if the robot is done moving the previously given move. Determines if a move command is finished, to within a small distance. If delta = 0 (default), the delta distance is what was set with setMoveDoneDist, you can get the distnace with getMoveDoneDist
|
|
Returns whether the robot is currently running or not.
|
|
Find out if the given sonar has a new reading.
|
|
Loads a parameter file (replacing all other params).
|
|
Logs the list of all tasks, strictly for your viewing pleasure.
|
|
Logs the list of user tasks, strictly for your viewing pleasure.
|
|
This function loops once... only serious developers should use it. This function is only for serious developers, it basically runs the loop once. You would use this function if you were wanting to use robot control in some other monolithic program, so you could work within its framework, rather than trying to get it to work in ARIA. |
|
Move the given distance forward/backwards
Tells the robot to move the specified distance forward/backwards, it caches this value, and sends it during the next cycle.
|
|
Moves the robot's RW position to reflect pose From => pose To.
|
|
Moves the robot's idea of its position to this position.
|
|
Packet Handler, internal. Reads in all of the packets that are available to read in, then runs through the list of packet handlers and tries to get each packet handled.
|
|
Removes an action from the list, by name. Finds the action with the given name and removes it from the actions... if more than one action has that name it find the one with the lowest priority
|
|
Removes an action from the list, by pointer. Finds the action with the given pointer and removes it from the actions... if more than one action has that pointer it find the one with the lowest priority
|
|
Adds a disconnect callback.
|
|
Removes a callback for when disconnect is called while connected.
|
|
Removes a callback for when disconnection happens because of an error.
|
|
Removes a callback for when a connection to the robot is failed.
|
|
Removes a packet handler from the list of packet handlers.
|
|
Remove a range device from the robot's list, by instance.
|
|
Remove a range device from the robot's list, by name.
|
|
Removes a callback for when the run loop exits for what ever reason.
|
|
Removes a sensor interp tasks by functor.
|
|
Removes a sensor interp tasks by name.
|
|
Removes stabilizing callback.
|
|
Removes a user task from the list of synchronous taskes by functor.
|
|
Removes a user task from the list of synchronous taskes by name.
|
|
Robot locker, internal. This just locks the robot, so that its locked for all the user tasks |
|
Robot unlocker, internal. This just unlocks the robot |
|
Starts the instance to do processing in this thread. This starts the list of tasks to be run through until stopped. This function doesn't return until something calls stop on this instance.
|
|
Starts the instance to do processing in its own new thread. This starts a new thread then has runs through the tasks until stopped. This function doesn't return until something calls stop on this instance. This function returns immediately
|
|
Sets the robots absolute maximum rotational velocity. This sets the absolute maximum velocity the robot will go... the maximum velocity can also be set by the actions and by setRotVelMax, but it will not be allowed to go higher than this value. You should not set this very often, if you want to manipulate this value you should use the actions or setRotVelMax.
|
|
Sets the robots absolute maximum translational velocity. This sets the absolute maximum velocity the robot will go... the maximum velocity can also be set by the actions and by setTransVelMax, but it will not be allowed to go higher than this value. You should not set this very often, if you want to manipulate this value you should use the actions or setTransVelMax.
|
|
Sets the multiplier for how many cycles ArRobot waits when connecting.
|
|
Sets the time without a response until connection assumed lost. Sets the number of seconds to go without a response from the robot until it is assumed that the connection with the robot has been broken and the disconnect on error events will happen. Note that this will only happen with the default packet handler.
|
|
Sets the number of ms between cycles. Sets the number of milliseconds between cycles, at each cycle is when all packets are processed, all sensors are interpretted, all actions are called, and all user tasks are serviced. Be warned, if you set this too small you could overflow your serial connection.
|
|
Sets the number of ms between cycles to warn over. Sets a time such that if the number of milliseconds between cycles goes over this then there will be an ArLog::log(ArLog::Normal) warning.
|
|
Sets the dead recon position of the robot.
|
|
Sets the delta heading
Sets a delta heading to the robot, it caches this value, and sends it during the next cycle.
|
|
Sets the connection this instance uses. Sets the connection this instance uses to the actual robot. This is where commands will be sent and packets will be received from
|
|
Sets the length of time a direct motion command will take precedence over actions, in milliseconds. The direct motion precedence time determines how long actions will be ignored after a direct motion command is given. If the direct motion precedence time is 0, then direct motion will take precedence over actions until a clearDirectMotion command is issued. This value defaults to 0.
|
|
Sets the encoderCorrectionCallback. This sets the encoderCorrectionCB, this callback returns the robots change in heading, it takes in the change in heading, x, and y, between the previous and current readings.
|
|
Changes the transform directly.
|
|
Changes the transform.
|
|
Sets the heading
Sets the heading of the robot, it caches this value, and sends it during the next cycle.
|
|
Sets the rotational velocity
Sets the rotational velocity of the robot, it caches this value, and sends it during the next cycle.
|
|
How long we should stabilize for in ms (0 disables stabilizing). This is the amount of time the robot will stabilize for after it has connected to the robot (it won't report it is connected until after this time is over). By convention you should never set this lower than what you find the value at (though it will let you) this is so that everything can get itself stabilized before we let things drive.
|
|
Sets the number of milliseconds between state reflection refreshes if the state has not changed. The state reflection refresh time is the number of milliseconds between when the state reflector will refresh the robot, if the command hasn't changed. The default is 500 milliseconds. If this number is less than the cyle time, it'll simply happen every cycle.
|
|
Sets the velocity
Sets the velocity of the robot, it caches this value, and sends it during the next cycle.
|
|
Sets the velocity of the wheels independently
Sets the velocity of each of the wheels on the robot independently. it caches this value, and sends it during the next cycle. Note that this cancels both translational velocity AND rotational velocity, and is canceled by any of the other direct motion commands.
|
|
State Reflector, internal. If state reflecting (really direct motion command reflecting) was enabled in the constructor (ArRobot::ArRobot) then this will see if there are any direct motion commands to send, and if not then send the command given by the actions. If state reflection is disabled this will send a pulse to the robot every state reflection refresh time (setStateReflectionRefreshTime), if you don't wish this to happen simply set this to a very large value. |
|
Stops the robot
Stops the robot, by telling it to have a translational velocity and rotational velocity of 0. Also note that if you are using actions, this will cause the actions to be ignored until the direct motion precedence timeout has been exceeded or clearDirectMotion is called. |
|
Stops the robot from doing any more processing. This stops this robot from running anymore. If it is stopping from a runAsync it will cause the thread to return (exit), if it is running from a normal run, it will just cause the run function to return.
|
|
Suspend calling thread until the ArRobot is connected. This will suspend the calling thread until the ArRobot's run loop has managed to connect with the robot. There is an optional paramater of milliseconds to wait for the ArRobot to connect. If msecs is set to 0, it will wait until the ArRobot connects. This function will never return if the robot can not be connected with. If you want to be able to handle that case within the calling thread, you must call waitForConnectOrConnFail().
|
|
Suspend calling thread until the ArRobot is connected or fails to connect. This will suspend the calling thread until the ArRobot's run loop has managed to connect with the robot or fails to connect with the robot. There is an optional paramater of milliseconds to wait for the ArRobot to connect. If msecs is set to 0, it will wait until the ArRobot connects.
|
|
Suspend calling thread until the ArRobot run loop has exited. This will suspend the calling thread until the ArRobot's run loop has exited. There is an optional paramater of milliseconds to wait for the ArRobot run loop to exit . If msecs is set to 0, it will wait until the ArRrobot run loop exits.
|
|
Wake up all threads waiting for connection or connection failure. This will wake all the threads waiting for the robot to be connected or waiting for the robot to fail to connect.
|
|
Wake up all threads waiting for connection. This will wake all the threads waiting for the robot to be connected.
|
|
Wake up all threads waiting for the run loop to exit. This will wake all the threads waiting for the run loop to exit.
|
|
Wake up all threads waiting on this robot. This will wake all the threads waiting for various major state changes in this particular ArRobot. This includes all threads waiting for the robot to be connected and all threads waiting for the run loop to exit. |