Main Page | Class Hierarchy | Alphabetical List | Class List | File List | Class Members | File Members | Related Pages | Examples

ArRobot Class Reference

#include <ArRobot.h>

List of all members.


Detailed Description

Central class for communicating with and operating the robot.

This is the most important class. It is used to communicate with the robot by sending commands and retrieving data (including wheel odometry, digital and analog inputs, sonar data, and more). It is also used to provide access to objects for controlling attached accessories, ArRangeDevice objects, ArAction objects, and others. For details on usage, and how the task cycle and obot state synchronization works, see the ArRobot section and the Commands and Actions section of the ARIA overview.

Note:
In Windows you cannot make an ArRobot object a global variable, it will crash because the compiler initializes the constructors in the wrong order. You can, however, make a pointer to an ArRobot and then allocate it with 'new' at program start.
See also:
ArSimpleConnector
Examples:

actionExample.cpp, actionGroupExample.cpp, actsColorFollowingExample.cpp, armExample.cpp, auxSerialExample.cpp, demo.cpp, directMotionExample.cpp, dpptuExample.cpp, gotoActionExample.cpp, gpsExample.cpp, gpsRobotTaskExample.cpp, gripperExample.cpp, gyroExample.cpp, joydriveActionExample.cpp, lineFinderExample.cpp, moduleExample.cpp, moduleExample_Mod.cpp, robotConnectionCallbacks.cpp, robotSyncTaskExample.cpp, simpleConnect.cpp, simpleMotionCommands.cpp, sonyPTZDemo.cpp, teleopActionsExample.cpp, triangleDriveToActionExample.cpp, vcc4CameraExample.cpp, and wander.cpp.


Public Types

enum  ChargeState {
  CHARGING_UNKNOWN = -1, CHARGING_NOT = 0, CHARGING_BULK = 1, CHARGING_OVERCHARGE = 2,
  CHARGING_FLOAT = 3
}
enum  WaitState {
  WAIT_CONNECTED, WAIT_FAILED_CONN, WAIT_RUN_EXIT, WAIT_TIMEDOUT,
  WAIT_INTR, WAIT_FAIL
}

Public Member Functions

void actionHandler (void)
 Action Handler, internal.
bool addAction (ArAction *action, int priority)
 Adds an action to the list with the given priority.
void addConnectCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST)
 Adds a connect callback.
void addDisconnectNormallyCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST)
 Adds a callback for when disconnect is called while connected.
void addDisconnectOnErrorCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST)
 Adds a callback for when disconnection happens because of an error.
void addFailedConnectCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST)
 Adds a callback for when a connection to the robot is failed.
bool addLaser (ArLaser *laser, int laserNumber, bool addAsRangeDevice=true)
 Adds a laser to the robot's map of them.
void addPacketHandler (ArRetFunctor1< bool, ArRobotPacket * > *functor, ArListPos::Pos position=ArListPos::LAST)
 Adds a packet handler to the list of packet handlers.
void addRangeDevice (ArRangeDevice *device)
 Adds a rangeDevice to the robot's list of them, and set the device's robot pointer.
void addRunExitCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST)
 Adds a callback for when the run loop exits for what ever reason.
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.
void addStabilizingCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST)
 Adds a callback called when the robot starts stabilizing before declaring connection.
bool addUserTask (const char *name, int position, ArFunctor *functor, ArTaskState::State *state=NULL)
 Adds a user task to the list of synchronous taskes.
void applyTransform (ArTransform trans, bool doCumulative=true)
 This applies a transform to all the robot range devices and to the sonar.
bool areMotorsEnabled (void) const
 returns true if the motors are enabled
bool areSonarsEnabled (void) const
 returns true if the sonars are enabled (note that if the robot has no sonars at all, this will return false)
void ariaExitCallback (void)
 internal function called when Aria::exit is called
 ArRobot (const char *name=NULL, bool ignored=true, bool doSigHandle=true, bool normalInit=true, bool addAriaExitCallback=true)
 Constructor.
bool asyncConnect (void)
 Connects to a robot, from the robots own thread.
int asyncConnectHandler (bool tryHarderToConnect)
 Internal function, shouldn't be used, does a single run of connecting.
void attachKeyHandler (ArKeyHandler *keyHandler, bool exitOnEscape=true, bool useExitNotShutdown=true)
 Attachs a key handler.
bool blockingConnect (void)
 Connects to a robot, not returning until connection made or failed.
void cancelConnection (void)
 Internal function, shouldn't be used, cancels the connection quietly.
double checkRangeDevicesCumulativeBox (double x1, double y1, double x2, double y2, ArPose *readingPos=NULL, const ArRangeDevice **rangeDevice=NULL, bool useLocationDependentDevices=true) const
double checkRangeDevicesCumulativePolar (double startAngle, double endAngle, double *angle=NULL, const ArRangeDevice **rangeDevice=NULL, bool useLocationDependentDevices=true) const
 Goes through all the range devices and checks them.
double checkRangeDevicesCurrentBox (double x1, double y1, double x2, double y2, ArPose *readingPos=NULL, const ArRangeDevice **rangeDevice=NULL, bool useLocationDependentDevices=true) const
double checkRangeDevicesCurrentPolar (double startAngle, double endAngle, double *angle=NULL, const ArRangeDevice **rangeDevice=NULL, bool useLocationDependentDevices=true) const
 Goes through all the range devices and checks them.
void clearDirectMotion (void)
 Clears what direct motion commands have been given, so actions work.
bool com (unsigned char command)
 Sends a command to the robot with no arguments.
bool com2Bytes (unsigned char command, char high, char low)
 Sends a command to the robot with two bytes for argument.
bool comDataN (unsigned char command, const char *data, int size)
 Sends a command containing exactly the data in the given buffer as argument.
bool comInt (unsigned char command, short int argument)
 Sends a command to the robot with an int for argument.
bool comStr (unsigned char command, const char *argument)
 Sends a command to the robot with a length-prefixed string for argument.
bool comStrN (unsigned char command, const char *str, int size)
 Sends a command to the robot with a length-prefixed string for argument.
void deactivateActions (void)
 Deactivates all the actions.
void disableMotors ()
 Disables the motors on the robot.
void disableSonar ()
 Disables the sonar on the robot.
bool disconnect (void)
 Disconnects from a robot.
void dropConnection (void)
 Internal function, shouldn't be used, drops the conn because of error.
void enableMotors ()
 Enables the motors on the robot.
void enableSonar ()
 Enables the sonar on the robot.
void failedConnect (void)
 Internal function, shouldn't be used, denotes the conn failed.
ArActionfindAction (const char *actionName)
 Returns the first (highest priority) action with the given name (or NULL).
double findAngleTo (const ArPose pose)
 Gets the angle to a point from the robot's current position and orientation.
double findDeltaHeadingTo (const ArPose pose)
 Gets the difference between the angle to a point from the robot's current heading.
double findDistanceTo (const ArPose pose)
 Gets the distance to a point from the robot's current position.
ArLaserfindLaser (int laserNumber)
 Finds a laser in the robot's list.
const ArLaserfindLaser (int laserNumber) const
 Finds a laser in the robot's list.
ArRangeDevicefindRangeDevice (const char *name, bool ignoreCase=false)
 Finds a rangeDevice in the robot's list.
const ArRangeDevicefindRangeDevice (const char *name, bool ignoreCase=false) const
 Finds a rangeDevice in the robot's list.
ArSyncTaskfindTask (ArFunctor *functor)
 Finds a task by functor.
ArSyncTaskfindTask (const char *name)
 Finds a task by name.
ArSyncTaskfindUserTask (ArFunctor *functor)
 Finds a user task by functor.
ArSyncTaskfindUserTask (const char *name)
 Finds a user task by name.
void finishedConnection (void)
 Internal function, shouldn't be used, does the after conn stuff.
void forceTryingToMove (void)
 Manually sets the flag that says the robot is trying to move for one cycle.
double getAbsoluteMaxLatAccel (void) const
 Gets the robot's absolute maximum lateral acceleration.
double getAbsoluteMaxLatDecel (void) const
 Gets the robot's absolute maximum lateral deceleration.
double getAbsoluteMaxLatVel (void) const
 Gets the robot's absolute maximum lateral velocity.
double getAbsoluteMaxRotAccel (void) const
 Gets the robot's absolute maximum rotational acceleration.
double getAbsoluteMaxRotDecel (void) const
 Gets the robot's absolute maximum rotational deceleration.
double getAbsoluteMaxRotVel (void) const
 Gets the robot's absolute maximum rotational velocity.
double getAbsoluteMaxTransAccel (void) const
 Gets the robot's absolute maximum translational acceleration.
double getAbsoluteMaxTransDecel (void) const
 Gets the robot's absolute maximum translational deceleration.
double getAbsoluteMaxTransVel (void) const
 Gets the robot's absolute maximum translational velocity.
ArResolver::ActionMapgetActionMap (void)
unsigned char getAnalog (void) const
 Gets the analog value.
int getAnalogPortSelected (void) const
 Gets which analog port is selected.
double getBatteryVoltage (void) const
 Gets the battery voltage of the robot (normalized to 12 volt system).
size_t getBatteryVoltageAverageOfNum (void)
 Gets the number of readings the battery voltage is the average of.
double getBatteryVoltageNow (void) const
 Gets the instaneous battery voltage.
ChargeState getChargeState (void) const
 Gets the charge state of the robot (see long docs).
int getClosestSonarNumber (double startAngle, double endAngle) const
 Returns the number of the sonar that has the closest current reading in the given range.
int getClosestSonarRange (double startAngle, double endAngle) const
 Returns the closest of the current sonar reading in the given range.
double getCompass (void) const
 Gets the compass heading from the robot.
unsigned int getConnectionCycleMultiplier (void) const
 Gets the multiplier for how many cycles ArRobot waits when connecting.
int getConnectionTimeoutTime (void) const
 Gets the time without a response until connection assumed lost.
double getControl (void) const
 Gets the control heading.
unsigned int getCounter (void) const
 Gets the Counter for the time through the loop.
unsigned int getCycleTime (void) const
 Gets the number of ms between cycles.
unsigned int getCycleWarningTime (void)
 Gets the number of ms between cycles to warn over.
unsigned int getCycleWarningTime (void) const
 Gets the number of ms between cycles to warn over.
ArDeviceConnectiongetDeviceConnection (void) const
 Gets the connection this instance uses.
unsigned char getDigIn (void) const
 Gets the byte representing digital input status.
unsigned char getDigOut (void) const
 Gets the byte representing digital output status.
unsigned int getDirectMotionPrecedenceTime (void) const
bool getDoNotSwitchBaud (void)
 Gets the flag that controls if the robot won't switch baud rates.
ArRetFunctor1< double, ArPoseWithTime > * getEncoderCorrectionCallback (void) const
 Gets the encoderCorrectionCallback.
ArPose getEncoderPose (void) const
 Get the position of the robot according to the last robot SIP, possibly with gyro correction if installed and enabled, but without any transformations applied.
size_t getEncoderPoseInterpNumReadings (void) const
 Sets the number of packets back in time the encoder position interpolation goes.
int getEncoderPoseInterpPosition (ArTime timeStamp, ArPose *position)
 Gets the encoder position the robot was at at the given timestamp.
ArTransform getEncoderTransform (void) const
 Gets the encoder transform.
bool getEstop (void)
 Returns true if the E-Stop button is pressed.
int getFaultFlags (void) const
 Gets the fault flags values.
int getFlags (void) const
 Gets the flags values.
double getHeadingDoneDiff (void) const
 Gets the difference required for being done with a heading change (e.g. used in isHeadingDone()).
int getIOAnalog (int num) const
 Gets the n'th byte from the analog input data from the IO packet.
int getIOAnalogSize (void) const
 Gets the number of bytes in the analog IO buffer.
double getIOAnalogVoltage (int num) const
 Gets the n'th byte from the analog input data from the IO packet.
unsigned char getIODigIn (int num) const
 Gets the n'th byte from the digital input data from the IO packet.
int getIODigInSize (void) const
 Gets the number of bytes in the digital input IO buffer.
unsigned char getIODigOut (int num) const
 Gets the n'th byte from the digital output data from the IO packet.
int getIODigOutSize (void) const
 Gets the number of bytes in the digital output IO buffer.
ArTime getIOPacketTime (void) const
 Returns the time received of the last IO packet.
ArKeyHandlergetKeyHandler (void) const
 Gets the key handler attached to this robot.
std::map< int, ArLaser * > * getLaserMap (void)
 Gets the range device list.
const std::map< int, ArLaser * > * getLaserMap (void) const
 Gets the range device list.
ArTime getLastOdometryTime (void) const
 Gets the time the last odometry was received.
ArTime getLastPacketTime (void) const
 Gets the time the last packet was received.
double getLatAccel (void) const
 Gets the lateral acceleration.
double getLatDecel (void) const
 Gets the lateral acceleration.
double getLatVel (void) const
 Gets the current lateral velocity of the robot.
double getLatVelMax (void) const
 Gets the maximum lateral velocity.
long int getLeftEncoder (void)
 Gets packet data from the left encoder.
double getLeftVel (void) const
 Gets the velocity of the left wheel.
bool getLogActions (void)
 Gets if we're logging all the actions as they happen.
bool getLogMovementReceived (void)
 Gets if we're logging all the positions received from the robot.
bool getLogMovementSent (void)
 Gets if we're logging all the movement commands sent down.
bool getLogVelocitiesReceived (void)
 Gets if we're logging all the velocities (and heading) received.
int getMotorPacCount (void) const
 Gets the number of motor packets received in the last second.
double getMoveDoneDist (void)
 Gets the difference required for being done with a move.
const char * getName (void) const
 Gets the robots name in ARIAs list.
bool getNoTimeWarningThisCycle (void)
 Internal function for sync loop and sync task to see if we should warn this cycle or not.
unsigned int getNumFrontBumpers (void) const
 Get the number of the front bumper switches.
unsigned int getNumRearBumpers (void) const
 Gets the number of rear bumper switches.
int getNumSonar (void) const
 Find the number of sonar sensors (that the robot has yet returned values for).
double getOdometerDegrees (void)
 This gets the number of degrees the robot has turned (deg).
double getOdometerDistance (void)
 This gets the distance the robot has travelled (mm).
double getOdometerTime (void)
 This gets the time since the robot started (sec).
int getOdometryDelay (void)
 Gets the delay in odometry readings.
const ArRobotConfigPacketReadergetOrigRobotConfig (void) const
 Gets the original robot config packet information.
ArThread::ThreadType getOSThread (void)
 Internal call that will get the thread the robot is running in.
bool getPacketsReceivedTracking (void)
 Gets if we're logging all the packets received (just times and types).
bool getPacketsSentTracking (void)
 Gets if we're logging all the packets sent and their payload.
ArPose getPose (void) const
 Get the current stored global position of the robot.
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.
ArPTZgetPTZ (void)
 Sets the camera this robot is using.
std::list< ArRangeDevice * > * getRangeDeviceList (void)
 Gets the range device list.
ArPose getRawEncoderPose (void) const
 Get the position of the robot according to the last robot SIP only, with no correction by the gyro, other devices or software proceses.
double getRealBatteryVoltage (void) const
 Gets the real battery voltage of the robot.
size_t getRealBatteryVoltageAverageOfNum (void)
 Gets the number of readings the battery voltage is the average of.
double getRealBatteryVoltageNow (void) const
 Gets the instaneous battery voltage.
ArResolvergetResolver (void)
 Gets the resolver the robot is using.
long int getRightEncoder (void)
 Gets packet data from the right encoder.
double getRightVel (void) const
 Gets the velocity of the right wheel.
double getRobotDiagonal (void) const
 Gets the robot diagonal (half-height to diagonal of octagon) (in mm).
double getRobotLength (void) const
 Gets the robot length (in mm).
double getRobotLengthFront (void) const
 Gets the robot length to the front (in mm).
double getRobotLengthRear (void) const
 Gets the robot length to the front (in mm).
const char * getRobotName (void) const
 Returns the robot's name that is set in its onboard firmware configuration.
const ArRobotParamsgetRobotParams (void) const
 Gets the parameters the robot is using.
double getRobotRadius (void) const
 Gets the robot radius (in mm).
const char * getRobotSubType (void) const
 Returns the subtype of the robot we are currently connected to.
const char * getRobotType (void) const
 Returns the type of the robot we are currently connected to.
double getRobotWidth (void) const
 Gets the robot width (in mm).
double getRotAccel (void) const
 Gets the rotational acceleration.
double getRotDecel (void) const
 Gets the rotational acceleration.
double getRotVel (void) const
 Gets the current rotational velocity of the robot.
double getRotVelMax (void) const
 Gets the maximum rotational velocity.
std::list< ArFunctor * > * getRunExitListCopy ()
 Internal function, shouldn't be used, does what its name says.
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.
ArSensorReadinggetSonarReading (int num) const
 Returns the sonar reading for the given sonar.
int getStabilizingTime (void) const
 How long we stabilize for in ms (0 means no stabilizng).
int getStallValue (void) const
 Gets the 2 bytes of stall and bumper flags from the robot.
double getStateOfCharge (void) const
 Gets the state of charge (percent of charge, as number between 0 and 100).
double getStateOfChargeLow (void) const
 Gets the state of charge that is considered low.
ArTime getStateOfChargeSetTime (void) const
 Gets the last time the state of charge was set.
double getStateOfChargeShutdown (void) const
 Gets the state of charge (percent of charge, as number between 0 and 100).
int getStateReflectionRefreshTime (void) const
ArSyncTaskgetSyncTaskRoot (void)
int getTemperature (void)
 Gets the temperature of the robot, -128 if not available, -127 to 127 otherwise.
double getTh (void) const
 Gets the global angular position ("theta") of the robot.
ArTransform getToGlobalTransform (void) const
 This gets the transform from local coords to global coords.
ArTransform getToLocalTransform (void) const
 This gets the transform for going from global coords to local coords.
double getTransAccel (void) const
 Gets the translational acceleration.
double getTransDecel (void) const
 Gets the translational acceleration.
double getTransVelMax (void) const
 Gets the maximum translational velocity.
double getTripOdometerDegrees (void)
 This gets the number of degrees the robot has turned since the last reset (deg).
double getTripOdometerDistance (void)
 This gets the distance the robot has travelled since the last reset (mm).
double getTripOdometerTime (void)
 This gets the time since the odometer was reset (sec).
double getVel (void) const
 Gets the current translational velocity of the robot.
double getX (void) const
 Gets the global X position of the robot.
double getY (void) const
 Gets the global Y position of the robot.
bool handlePacket (ArRobotPacket *packet)
bool hasFaultFlags (void) const
 Gets whether or not we're getting the fault flags values.
bool hasFrontBumpers (void) const
 Gets whether the robot has front bumpers (see ARCOS parameters in the robot manual).
bool hasLaser (ArLaser *device) const
 Finds whether a particular range device is attached to this robot or not.
bool hasLatVel (void) const
 Sees if the robot supports lateral velocities (e.g. Seekur(TM)).
bool hasRangeDevice (ArRangeDevice *device) const
 Finds whether a particular range device is attached to this robot or not.
bool hasRearBumpers (void) const
 Gets whether the robot has rear bumpers (see ARCOS parameters in the robot manual).
bool hasSettableAccsDecs (void) const
 If the robot has settable accels and decels.
bool hasSettableVelMaxes (void) const
 If the robot has settable maximum velocities.
bool hasTableSensingIR (void) const
 Gets whether the robot has table sensing IR or not (see params in docs).
bool hasTemperature (void)
 Returns true if we have a temperature, false otherwise.
bool haveStateOfCharge (void) const
 Gets if the state of charge value is in use.
void incCounter (void)
 This is only for use by syncLoop.
void init (void)
 Internal function, shouldn't be used.
bool isConnected (void) const
 Questions whether the robot is connected or not.
bool isCycleChained (void) const
 Gets whether we chain the robot cycle to when we get in SIP packets.
bool isDirectMotion (void) const
 Returns true if direct motion commands are blocking actions.
bool isEStopPressed (void) const
 returns true if the estop is pressed (or unrelieved)
bool isHeadingDone (double delta=0.0) const
 Sees if the robot is done changing to the previously given setHeading.
bool isLeftBreakBeamTriggered (void) const
 Returns true if the left break beam IR is triggered.
bool isLeftMotorStalled (void) const
 Returns true if the left motor is stalled.
bool isLeftTableSensingIRTriggered (void) const
 Returns true if the left table sensing IR is triggered.
bool isMoveDone (double delta=0.0)
 Sees if the robot is done moving the previously given move.
bool isRightBreakBeamTriggered (void) const
 Returns true if the right break beam IR is triggered.
bool isRightMotorStalled (void) const
 Returns true if the left motor is stalled.
bool isRightTableSensingIRTriggered (void) const
 Returns true if the right table sensing IR is triggered.
bool isRunning (void) const
 Returns whether the robot is currently running or not.
bool isSonarNew (int num) const
 Find out if the given sonar reading was newly refreshed by the last incoming SIP received.
bool isStabilizing (void)
 This tells us if we're in the preconnection state.
bool isTryingToMove (void)
 Gets if the robot is trying to move or not.
void keyHandlerExit (void)
 For the key handler, escape calls this to exit, internal.
bool loadParamFile (const char *file)
 Loads a parameter file (replacing all other params).
int lock ()
 Lock the robot instance.
void logActions (bool logDeactivated=false) const
 Logs out the actions and their priorities.
void logAllTasks (void) const
 Logs the list of all tasks, strictly for your viewing pleasure.
void logUserTasks (void) const
 Logs the list of user tasks, strictly for your viewing pleasure.
void loopOnce (void)
 This function loops once... only serious developers should use it.
bool madeConnection (void)
 Internal function, shouldn't be used, does the initial conn stuff.
void move (double distance)
 Move the given distance forward/backwards.
void moveTo (ArPose to, ArPose from, bool doCumulative=true)
 Change stored pose (i.e. the value returned by getPose()).
void moveTo (ArPose pose, bool doCumulative=true)
 Change stored pose (i.e. the value returned by getPose()).
void packetHandler (void)
 Packet Handler, internal.
bool processEncoderPacket (ArRobotPacket *packet)
 Processes a new encoder packet, internal.
bool processIOPacket (ArRobotPacket *packet)
 Processes a new IO packet, internal.
bool processMotorPacket (ArRobotPacket *packet)
 Processes a motor packet, internal.
void processNewSonar (char number, int range, ArTime timeReceived)
 Processes a new sonar reading, internal.
void processParamFile (void)
 Internal function, processes a parameter file.
bool remAction (const char *actionName)
 Removes an action from the list, by name.
bool remAction (ArAction *action)
 Removes an action from the list, by pointer.
void remConnectCB (ArFunctor *functor)
 Removes a connect callback.
void remDisconnectNormallyCB (ArFunctor *functor)
 Removes a callback for when disconnect is called while connected.
void remDisconnectOnErrorCB (ArFunctor *functor)
 Removes a callback for when disconnection happens because of an error.
void remFailedConnectCB (ArFunctor *functor)
 Removes a callback for when a connection to the robot is failed.
bool remLaser (int laserNumber, bool removeAsRangeDevice=true)
 Remove a range device from the robot's list, by number.
bool remLaser (ArLaser *laser, bool removeAsRangeDevice=true)
 Remove a range device from the robot's list, by instance.
void remPacketHandler (ArRetFunctor1< bool, ArRobotPacket * > *functor)
 Removes a packet handler from the list of packet handlers.
void remRangeDevice (ArRangeDevice *device)
 Remove a range device from the robot's list, by instance.
void remRangeDevice (const char *name)
 Remove a range device from the robot's list, by name.
void remRunExitCB (ArFunctor *functor)
 Removes a callback for when the run loop exits for what ever reason.
void remSensorInterpTask (ArFunctor *functor)
 Removes a sensor interp tasks by functor.
void remSensorInterpTask (const char *name)
 Removes a sensor interp tasks by name.
void remStabilizingCB (ArFunctor *functor)
 Removes stabilizing callback.
void remUserTask (ArFunctor *functor)
 Removes a user task from the list of synchronous taskes by functor.
void remUserTask (const char *name)
 Removes a user task from the list of synchronous taskes by name.
void requestEncoderPackets (void)
 Starts a continuous stream of encoder packets.
void requestIOPackets (void)
 Starts a continuous stream of IO packets.
void resetTripOdometer (void)
 Resets the odometer.
void robotLocker (void)
 Robot locker, internal.
void robotUnlocker (void)
 Robot unlocker, internal.
void run (bool stopRunIfNotConnected)
 Starts the instance to do processing in this thread.
void runAsync (bool stopRunIfNotConnected)
 Starts the instance to do processing in its own new thread.
bool setAbsoluteMaxLatAccel (double maxAccel)
 Sets the robot's absolute maximum lateral acceleration.
bool setAbsoluteMaxLatDecel (double maxDecel)
 Sets the robot's absolute maximum lateral deceleration.
bool setAbsoluteMaxLatVel (double maxVel)
 Sets the robot's absolute maximum lateral velocity.
bool setAbsoluteMaxRotAccel (double maxAccel)
 Sets the robot's absolute maximum rotational acceleration.
bool setAbsoluteMaxRotDecel (double maxDecel)
 Sets the robot's absolute maximum rotational deceleration.
bool setAbsoluteMaxRotVel (double maxVel)
 Sets the robot's absolute maximum rotational velocity.
bool setAbsoluteMaxTransAccel (double maxAccel)
 Sets the robot's absolute maximum translational acceleration.
bool setAbsoluteMaxTransDecel (double maxDecel)
 Sets the robot's absolute maximum translational deceleration.
bool setAbsoluteMaxTransVel (double maxVel)
 Sets the robot's absolute maximum translational velocity.
void setBatteryVoltageAverageOfNum (size_t numToAverage)
 Sets the number of readings the battery voltage is the average of (default 20).
void setChargeState (ArRobot::ChargeState chargeState)
 Sets the charge state (for use with setting the state of charge).
void setConnectionCycleMultiplier (unsigned int multiplier)
 Sets the multiplier for how many cycles ArRobot waits when connecting.
void setConnectionTimeoutTime (int mSecs)
 Sets the time without a response until connection assumed lost.
void setConnectWithNoParams (bool connectWithNoParams)
 internal call that will let the robot connect even if it can't find params
void setCycleChained (bool cycleChained)
 Sets whether to chain the robot cycle to when we get in SIP packets.
void setCycleTime (unsigned int ms)
 Sets the number of ms between cycles.
void setCycleWarningTime (unsigned int ms)
 Sets the number of ms between cycles to warn over.
void setDeadReconPose (ArPose pose)
 Sets the dead recon position of the robot.
void setDeltaHeading (double deltaHeading)
 Sets the delta heading.
void setDeviceConnection (ArDeviceConnection *connection)
 Sets the connection this instance uses.
void setDirectMotionPrecedenceTime (int mSec)
void setDoNotSwitchBaud (bool doNotSwitchBaud)
 Sets the flag that controls if the robot will switch baud rates.
void setEncoderCorrectionCallback (ArRetFunctor1< double, ArPoseWithTime > *functor)
 Sets the encoderCorrectionCallback.
void setEncoderPoseInterpNumReadings (size_t numReadings)
 Sets the number of packets back in time the ArInterpolation goes for encoder readings.
void setEncoderTransform (ArPose transformPos)
 Changes the transform directly.
void setEncoderTransform (ArPose deadReconPos, ArPose globalPos)
 Changes the transform.
void setHeading (double heading)
 Sets the heading.
void setHeadingDoneDiff (double degrees)
 sets the difference required for being done with a heading change (e.g. used in isHeadingDone())
void setLatAccel (double acc)
 Sets the lateral acceleration.
void setLatDecel (double decel)
 Sets the lateral acceleration.
void setLatVel (double latVelocity)
void setLatVelMax (double vel)
 Sets the maximum lateral velocity.
void setLogActions (bool logActions)
 Sets if we're logging all the actions as they happen.
void setLogMovementReceived (bool logMovementReceived)
 Sets if we're logging all the positions received from the robot.
void setLogMovementSent (bool logMovementSent)
 Sets if we're logging all the movement commands sent down.
void setLogVelocitiesReceived (bool logVelocitiesReceived)
 Sets if we're logging all the velocities (and heading) received.
void setMoveDoneDist (double dist)
 Sets the difference required for being done with a move.
void setMutexLockWarningTime (double sec)
 Set robot lock warning time (see ArMutex::setLockWarningTime()).
void setMutexLogging (bool v)
 Turn on verbose locking of robot mutex.
void setMutexUnlockWarningTime (double sec)
 Set robot lock-unlock warning time (see ArMutex::setUnlockWarningTime()).
void setName (const char *name)
 Sets the robots name in ARIAs list.
void setNoTimeWarningThisCycle (bool noTimeWarningThisCycle)
 Internal function for sync loop and sync task to say if we should warn this cycle or not.
void setOdometryDelay (int msec)
 Sets the delay in the odometry readings.
void setPacketsReceivedTracking (bool packetsReceivedTracking)
 Sets if we're logging all the packets received (just times and types).
void setPacketsSentTracking (bool packetsSentTracking)
 Sets if we're logging all the packets sent and their payloads.
void setPoseInterpNumReadings (size_t numReadings)
 Sets the number of packets back in time the ArInterpolation goes.
void setPTZ (ArPTZ *ptz)
 Sets the camera this robot is using.
void setRealBatteryVoltageAverageOfNum (size_t numToAverage)
 Sets the number of readings the real battery voltage is the average of (default 20).
void setResolver (ArResolver *resolver)
 Sets the resolver the robot is using.
void setRobotParams (ArRobotParams *params)
 Sets the robot to use a passed in set of params (passes ownership).
void setRotAccel (double acc)
 Sets the rotational acceleration.
void setRotDecel (double decel)
 Sets the rotational acceleration.
void setRotVel (double velocity)
 Sets the rotational velocity.
void setRotVelMax (double vel)
 Sets the maximum rotational velocity.
void setStabilizingTime (int mSecs)
 How long we should stabilize for in ms (0 disables stabilizing).
void setStateOfCharge (double stateOfCharge)
 Manually sets the current percentage that the robot is charged (argument is percentage, as a number between 0 and 100).
void setStateOfChargeLow (double stateOfChargeLow)
 Sets the state of charge (percentage) that is considered to be low.
void setStateOfChargeShutdown (double stateOfChargeShutdown)
 Sets the state of charge that will cause a shutdown.
void setStateReflectionRefreshTime (int msec)
void setTransAccel (double acc)
 Sets the translational acceleration.
void setTransDecel (double decel)
 Sets the translational acceleration.
void setTransVelMax (double vel)
 Sets the maximum translational velocity.
void setUpPacketHandlers (void)
 Internal function, shouldn't be used, sets up the default packet handlers.
void setUpSyncList (void)
 Internal function, shouldn't be used, sets up the default sync list.
void setVel (double velocity)
void setVel2 (double leftVelocity, double rightVelocity)
 Sets the velocity of the wheels independently.
void startStabilization (void)
 Internal function, shouldn't be used, calls the preconnected stuff.
void stateReflector (void)
 State Reflector, internal.
void stop (void)
void stopEncoderPackets (void)
 Stops a continuous stream of encoder packets.
void stopIOPackets (void)
 Stops a continuous stream of IO packets.
void stopRunning (bool doDisconnect=true)
 Stops the robot from doing any more processing.
void stopStateReflection (void)
int tryLock ()
 Try to lock the robot instance without blocking.
int unlock ()
 Unlock the robot instance.
WaitState waitForConnect (unsigned int msecs=0)
 Suspend calling thread until the ArRobot is connected.
WaitState waitForConnectOrConnFail (unsigned int msecs=0)
 Suspend calling thread until the ArRobot is connected or fails to connect.
WaitState waitForRunExit (unsigned int msecs=0)
 Suspend calling thread until the ArRobot run loop has exited.
void wakeAllConnOrFailWaitingThreads ()
 Wake up all threads waiting for connection or connection failure.
void wakeAllConnWaitingThreads ()
 Wake up all threads waiting for connection.
void wakeAllRunExitWaitingThreads ()
 Wake up all threads waiting for the run loop to exit.
void wakeAllWaitingThreads ()
 Wake up all threads waiting on this robot.
 ~ArRobot ()
 Destructor.

Public Attributes

ArFunctorC< ArRobotmyActionHandlerCB
ArRetFunctor1C< bool, ArRobot,
ArRobotPacket * > 
myEncoderPacketCB
ArRetFunctorC< unsigned int,
ArRobot
myGetCycleWarningTimeCB
ArRetFunctorC< bool, ArRobotmyGetNoTimeWarningThisCycleCB
ArRetFunctor1C< bool, ArRobot,
ArRobotPacket * > 
myIOPacketCB
ArFunctorC< ArKeyHandler > * myKeyHandlerCB
ArFunctorC< ArRobotmyKeyHandlerExitCB
ArRetFunctor1C< bool, ArRobot,
ArRobotPacket * > 
myMotorPacketCB
ArFunctorC< ArRobotmyPacketHandlerCB
ArFunctorC< ArRobotmyRobotLockerCB
ArFunctorC< ArRobotmyRobotUnlockerCB
ArFunctorC< ArRobotmyStateReflectorCB

Protected Types

enum  LatDesired { LAT_NONE, LAT_IGNORE, LAT_VEL }
enum  RotDesired { ROT_NONE, ROT_IGNORE, ROT_HEADING, ROT_VEL }
enum  TransDesired {
  TRANS_NONE, TRANS_IGNORE, TRANS_VEL, TRANS_VEL2,
  TRANS_DIST, TRANS_DIST_NEW
}

Protected Member Functions

void reset (void)

Protected Attributes

double myAbsoluteMaxLatAccel
double myAbsoluteMaxLatDecel
double myAbsoluteMaxLatVel
double myAbsoluteMaxRotAccel
double myAbsoluteMaxRotDecel
double myAbsoluteMaxRotVel
double myAbsoluteMaxTransAccel
double myAbsoluteMaxTransDecel
double myAbsoluteMaxTransVel
ArActionDesired myActionDesired
bool myActionLatSet
bool myActionRotSet
ArResolver::ActionMap myActions
bool myActionTransSet
bool myAddedAriaExitCB
unsigned char myAnalog
int myAnalogPortSelected
ArFunctorC< ArRobotmyAriaExitCB
bool myAsyncConnectFlag
int myAsyncConnectNoPacketCount
bool myAsyncConnectSentChangeBaud
int myAsyncConnectStartBaud
ArTime myAsyncConnectStartedChangeBaud
int myAsyncConnectState
int myAsyncConnectTimesTried
ArTime myAsyncStartedConnection
ArRunningAverage myBatteryAverager
double myBatteryVoltage
bool myBlockingConnectRun
ChargeState myChargeState
double myCompass
ArDeviceConnectionmyConn
std::list< ArFunctor * > myConnectCBList
ArCondition myConnectCond
unsigned int myConnectionCycleMultiplier
bool myConnectWithNoParams
ArCondition myConnOrFailCond
double myControl
unsigned int myCounter
bool myCycleChained
unsigned int myCycleTime
unsigned int myCycleWarningTime
unsigned char myDigIn
unsigned char myDigOut
int myDirectPrecedenceTime
std::list< ArFunctor * > myDisconnectNormallyCBList
std::list< ArFunctor * > myDisconnectOnErrorCBList
bool myDoNotSwitchBaud
ArRetFunctor1< double, ArPoseWithTime > * myEncoderCorrectionCB
ArTransform myEncoderGlobalTrans
ArInterpolation myEncoderInterpolation
ArPoseWithTime myEncoderPose
ArTime myEncoderPoseTaken
ArTransform myEncoderTransform
std::list< ArFunctor * > myFailedConnectCBList
int myFaultFlags
bool myFirstEncoderPose
int myFlags
ArPose myGlobalPose
bool myHasFaultFlags
bool myHaveStateOfCharge
double myHeadingDoneDiff
ArInterpolation myInterpolation
int myIOAnalog [128]
int myIOAnalogSize
unsigned char myIODigIn [255]
int myIODigInSize
unsigned char myIODigOut [255]
int myIODigOutSize
bool myIsConnected
bool myIsStabilizing
ArKeyHandlermyKeyHandler
bool myKeyHandlerUseExitNotShutdown
std::map< int, ArLaser * > myLaserMap
int myLastActionLatVal
bool myLastActionRotHeading
bool myLastActionRotStopped
int myLastActionRotVal
int myLastActionTransVal
double myLastCalculatedRotVel
double myLastHeading
ArTime myLastIOPacketReceivedTime
ArTime myLastLatSent
LatDesired myLastLatType
int myLastLatVal
double myLastLatVel
ArTime myLastOdometryReceivedTime
ArTime myLastPacketReceivedTime
ArTime myLastPulseSent
ArTime myLastRotSent
RotDesired myLastRotType
int myLastRotVal
double myLastRotVel
double myLastSentLatAccel
double myLastSentLatDecel
double myLastSentLatVelMax
double myLastSentRotAccel
double myLastSentRotDecel
double myLastSentRotVelMax
double myLastSentTransAccel
double myLastSentTransDecel
double myLastSentTransVelMax
int myLastTh
ArTime myLastTransSent
TransDesired myLastTransType
int myLastTransVal
int myLastTransVal2
double myLastVel
int myLastX
int myLastY
double myLatAccel
double myLatDecel
ArTime myLatSetTime
LatDesired myLatType
double myLatVal
double myLatVel
double myLatVelMax
long int myLeftEncoder
double myLeftVel
bool myLogActions
bool myLogMovementReceived
bool myLogMovementSent
bool myLogVelocitiesReceived
int myMotorPacCount
int myMotorPacCurrentCount
double myMoveDoneDist
ArMutex myMutex
std::string myName
bool myNoTimeWarningThisCycle
int myNumSonar
double myOdometerDegrees
double myOdometerDistance
ArTime myOdometerStart
int myOdometryDelay
ArRobotConfigPacketReadermyOrigRobotConfig
bool myOverriddenChargeState
bool myOwnTheResolver
std::list< ArRetFunctor1<
bool, ArRobotPacket * > * > 
myPacketHandlerList
bool myPacketsReceivedTracking
long myPacketsReceivedTrackingCount
ArTime myPacketsReceivedTrackingStarted
bool myPacketsSentTracking
ArRobotParamsmyParams
ArPTZmyPtz
std::list< ArRangeDevice * > myRangeDeviceList
ArPoseWithTime myRawEncoderPose
ArRunningAverage myRealBatteryAverager
double myRealBatteryVoltage
ArRobotPacketReceiver myReceiver
bool myRequestedEncoderPackets
bool myRequestedIOPackets
ArResolvermyResolver
long int myRightEncoder
double myRightVel
double myRobotLengthFront
double myRobotLengthRear
std::string myRobotName
std::string myRobotSubType
std::string myRobotType
double myRotAccel
double myRotDecel
ArTime myRotSetTime
RotDesired myRotType
double myRotVal
double myRotVel
double myRotVelMax
std::list< ArFunctor * > myRunExitCBList
ArCondition myRunExitCond
ArRobotPacketSender mySender
bool mySentPulse
int mySonarPacCount
int mySonarPacCurrentCount
std::map< int, ArSensorReading * > mySonars
std::list< ArFunctor * > myStabilizingCBList
int myStabilizingTime
int myStallValue
ArTime myStartedStabilizing
double myStateOfCharge
double myStateOfChargeLow
ArTime myStateOfChargeSetTime
double myStateOfChargeShutdown
int myStateReflectionRefreshTime
ArSyncLoop mySyncLoop
ArSyncTaskmySyncTaskRoot
char myTemperature
time_t myTimeLastMotorPacket
time_t myTimeLastSonarPacket
int myTimeoutTime
double myTransAccel
double myTransDecel
ArPose myTransDistStart
ArTime myTransSetTime
TransDesired myTransType
double myTransVal
double myTransVal2
double myTransVelMax
double myTripOdometerDegrees
double myTripOdometerDistance
ArTime myTripOdometerStart
bool myTryingToMove
double myVel
bool myWarnedAboutExtraSonar


Member Enumeration Documentation

enum ArRobot::WaitState
 

Enumeration values:
WAIT_CONNECTED  The robot has connected.
WAIT_FAILED_CONN  The robot failed to connect.
WAIT_RUN_EXIT  The run loop has exited.
WAIT_TIMEDOUT  The wait reached the timeout specified.
WAIT_INTR  The wait was interupted by a signal.
WAIT_FAIL  The wait failed due to an error.


Constructor & Destructor Documentation

ArRobot::ArRobot const char *  name = NULL,
bool  obsolete = true,
bool  doSigHandle = true,
bool  normalInit = true,
bool  addAriaExitCallback = true
 

Constructor.

The parameters only rarely need to be specified.

Parameters:
name A name for this robot, useful if a program has more than one ArRobot object
obsolete This parameter is ignored. (It used to turn off state reflection if false, but that is no longer possible.)
doSigHandle do normal signal handling and have this robot instance stopRunning() when the program is signaled
normalInit whether the robot should initializes its structures or the calling program will take care of it. No one will probalby ever use this value, since if they are doing that then overriding will probably be more useful, but there it is.
addAriaExitCallback If true (default), add callback to global Aria class to stop running the processing loop and disconnect from robot when Aria::exit() is called. If false, do not disconnect on Aria::exit()


Member Function Documentation

void ArRobot::actionHandler void   ) 
 

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.

See also:
addAction

remAction

bool ArRobot::addAction ArAction action,
int  priority
 

Adds an action to the list with the given priority.

Adds an action to the list of actions with 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. The default resolver (ArPriorityResolver) resolves the actions in order of descending priority. For example, an action with priority 100 is evaluated before one with priority 99, followed by 50, etc. This means that an action with a higher priority may be able to supercede a lower-priority action's desired value for a certain output to a lesser or greater degree, depending on how high a "strength" value it sets. See the overview of ARIA in this reference manual for more discussion on Actions.

Parameters:
action the action to add
priority what importance to give the action; how to order the actions. High priority actions are evaluated by the action resolvel before lower priority actions.
Returns:
true if the action was successfully added, false on error (e.g. the action was NULL)
See also:
remAction(ArAction*)

remAction(const char*)

findAction(const char*)

Examples:
actionExample.cpp, actsColorFollowingExample.cpp, gotoActionExample.cpp, gpsRobotTaskExample.cpp, gripperExample.cpp, gyroExample.cpp, joydriveActionExample.cpp, teleopActionsExample.cpp, triangleDriveToActionExample.cpp, and wander.cpp.

void ArRobot::addConnectCB ArFunctor functor,
ArListPos::Pos  position = ArListPos::LAST
 

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.

Parameters:
functor A functor (created from ArFunctorC) which refers to the function to call.
position whether to place the functor first or last
See also:
remConnectCB
Examples:
directMotionExample.cpp, and robotConnectionCallbacks.cpp.

void ArRobot::addDisconnectNormallyCB ArFunctor functor,
ArListPos::Pos  position = ArListPos::LAST
 

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.

Parameters:
functor functor created from ArFunctorC which refers to the function to call.
position whether to place the functor first or last
See also:
remFailedConnectCB

void ArRobot::addDisconnectOnErrorCB ArFunctor functor,
ArListPos::Pos  position = ArListPos::LAST
 

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.

Parameters:
functor functor created from ArFunctorC which refers to the function to call.
position whether to place the functor first or last
See also:
remDisconnectOnErrorCB

void ArRobot::addFailedConnectCB ArFunctor functor,
ArListPos::Pos  position = ArListPos::LAST
 

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.

Parameters:
functor functor created from ArFunctorC which refers to the function to call.
position whether to place the functor first or last
See also:
remFailedConnectCB

void ArRobot::addPacketHandler ArRetFunctor1< bool, ArRobotPacket * > *  functor,
ArListPos::Pos  position = ArListPos::LAST
 

Adds a packet handler to the list of packet handlers.

Adds a packet handler. A packet handler is an ArRetFunctor1<bool, ArRobotPacket*>, (e.g. 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 a list of functors to call when a packet arrives. This list is processed in order until one of the handlers returns true. Your packet handler function may be invoked for any packet, so it should test the packet type ID (see ArRobotPacket::getID()). If you handler gets data from the packet (it "handles" it) it should return true, to prevent ArRobot from invoking other handlers with the packet (with data removed). If you hander cannot interpret the packet, it should leave it unmodified and return false to allow other handlers a chance to receive it.

Parameters:
functor the functor to call when the packet comes in
position whether to place the functor first or last
See also:
remPacketHandler
Examples:
auxSerialExample.cpp.

void ArRobot::addRunExitCB ArFunctor functor,
ArListPos::Pos  position = ArListPos::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.

Parameters:
functor functor created from ArFunctorC which refers to the function to call.
position whether to place the functor first or last
See also:
remRunExitCB

bool ArRobot::addSensorInterpTask const char *  name,
int  position,
ArFunctor functor,
ArTaskState::State state = NULL
 

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).

Parameters:
name the name to give to the task, should be unique
position the place in the list of user tasks to place this task, this can be any integer, though by convention 0 to 100 is used. The tasks are called in order of highest number to lowest number.
functor functor created from ArFunctorC which refers to the function to call.
state Optional pointer to external ArSyncTask state variable; normally not needed and may be NULL or omitted.
See also:
remSensorInterpTask
Examples:
dpptuExample.cpp, robotSyncTaskExample.cpp, and vcc4CameraExample.cpp.

void ArRobot::addStabilizingCB ArFunctor functor,
ArListPos::Pos  position = ArListPos::LAST
 

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).

Parameters:
functor The functor to call (e.g. ArFunctorC)
position whether to place the functor first or last
See also:
remConnectCB

bool ArRobot::addUserTask const char *  name,
int  position,
ArFunctor functor,
ArTaskState::State state = NULL
 

Adds a user task to the list of synchronous taskes.

The synchronous tasks get called every robot cycle (every 100 ms by default).

Parameters:
name the name to give to the task, should be unique
position the place in the list of user tasks to place this task, this can be any integer, though by convention 0 to 100 is used. The tasks are called in order of highest number to lowest position number.
functor functor created from ArFunctorC which refers to the function to call.
state Optional pointer to external ArSyncTask state variable; normally not needed and may be NULL or omitted.
See also:
remUserTask
Examples:
gripperExample.cpp, gyroExample.cpp, and sonyPTZDemo.cpp.

void ArRobot::applyTransform ArTransform  trans,
bool  doCumulative = true
 

This applies a transform to all the robot range devices and to the sonar.

Applies a transform to the range devices and sonar... this is mostly useful for translating to/from local/global coords, but may have other uses

Parameters:
trans the transform to apply
doCumulative whether to transform the cumulative buffers or not

bool ArRobot::asyncConnect void   ) 
 

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 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).

Returns:
true if the robot is running and the robot will try to connect, false if the robot isn't running so won't try to connect or if the robot is already connected
See also:
addConnectCB

addFailedConnectCB

runAsync

int ArRobot::asyncConnectHandler bool  tryHarderToConnect  ) 
 

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.

Parameters:
tryHarderToConnect if this is true, then if the radio modems look like they aren't working, it'll take about 2 seconds to try and connect them, whereas if its false, it'll do a little try, but won't try very hard
Returns:
0 if its still trying to connect, 1 if it connected, 2 if it failed

void ArRobot::attachKeyHandler ArKeyHandler keyHandler,
bool  exitOnEscape = true,
bool  useExitNotShutdown = true
 

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.

Parameters:
keyHandler the key handler to attach
exitOnEscape whether to exit when escape is pressed or not
useExitNotShutdown if true then Aria::exit will be called instead of Aria::shutdown if it tries to exit
Examples:
actionGroupExample.cpp, actsColorFollowingExample.cpp, demo.cpp, gotoActionExample.cpp, gripperExample.cpp, lineFinderExample.cpp, triangleDriveToActionExample.cpp, and wander.cpp.

bool ArRobot::blockingConnect void   ) 
 

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 separate 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 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 (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).

Returns:
true if a connection could be made, false otherwise
Examples:
sonyPTZDemo.cpp, and vcc4CameraExample.cpp.

double ArRobot::checkRangeDevicesCumulativeBox double  x1,
double  y1,
double  x2,
double  y2,
ArPose readingPos = NULL,
const ArRangeDevice **  rangeDevice = NULL,
bool  useLocationDependentDevices = true
const
 

Gets the closest reading in a region defined by the two points of a rectangle. This goes through all of the registered range devices and locks each, calls cumulativeReadingBox() on it, and then unlocks it. If a reading was found in the box, returns with results.

Parameters:
x1 the x coordinate of one of the rectangle points
y1 the y coordinate of one of the rectangle points
x2 the x coordinate of the other rectangle point
y2 the y coordinate of the other rectangle point
readingPos If not NULL, a pointer to a position in which to store the location of the closest position
rangeDevice If not NULL, a pointer in which to store a pointer to the range device that provided the closest reading in the box.
Returns:
If >= 0 then this is the distance to the closest reading. If < 0 then there were no readings in the given region

double ArRobot::checkRangeDevicesCumulativePolar double  startAngle,
double  endAngle,
double *  angle = NULL,
const ArRangeDevice **  rangeDevice = NULL,
bool  useLocationDependentDevices = true
const
 

Goes through all the range devices and checks them.

Find the closest reading from any range device's set of cumulative readings within a polar region or "slice" defined by the given angle range. This function iterates through each registered range device (see addRangeDevice()), calls ArRangeDevice::lockDevice(), uses ArRangeDevice::cumulativeReadingPolar() to find a reading, then calls ArRangeDevice::unlockDevice().

The closest reading in this range device's cumulative buffer within a polar region or "slice" defined by the given angle range is returned. Optionally return the specific angle of the found reading as well. The region searched is the region between a starting angle, sweeping counter-clockwise to the ending angle (0 is straight ahead of the device, -90 to the right, 90 to the left). Note that there is a difference between the region (0, 10) and (10, 0). (0, 10) is a 10-degree span near the front of the device, while (10, 0) is a 350 degree span covering the sides and rear. Similarly, (-60, -30) covers 30 degrees on the right hand side, while (-30, -60) covers 330 degrees. In other words, if you want the smallest section between the two angles, ensure than startAngle < endAngle.

Parameters:
startAngle where to start the slice
endAngle where to end the slice, going counterclockwise from startAngle
angle if given, a pointer to a value in which to put the specific angle to the found reading
Returns:
the range to the obstacle (a value >= the maximum range indicates that no reading was detected in the specified region)
Example:
ArRangeDevice_currentReadingPolar.png

This figure illustrates an example range device and the meanings of arguments and return value.

Parameters:
rangeDevice If not null, then a pointer to the ArRangeDevice that provided the returned reading is placed in this variable.

double ArRobot::checkRangeDevicesCurrentBox double  x1,
double  y1,
double  x2,
double  y2,
ArPose readingPos = NULL,
const ArRangeDevice **  rangeDevice = NULL,
bool  useLocationDependentDevices = true
const
 

Gets the closest reading in a region defined by the two points of a rectangle. This goes through all of the registered range devices and locks each, calls currentReadingBox on it, and then unlocks it.

Parameters:
x1 the x coordinate of one of the rectangle points
y1 the y coordinate of one of the rectangle points
x2 the x coordinate of the other rectangle point
y2 the y coordinate of the other rectangle point
readingPos a pointer to a position in which to store the location of
rangeDevice If not null, then a pointer to the ArRangeDevice that provided the returned reading is placed in this variable. the closest position
Returns:
If >= 0 then this is the distance to the closest reading. If < 0 then there were no readings in the given region

double ArRobot::checkRangeDevicesCurrentPolar double  startAngle,
double  endAngle,
double *  angle = NULL,
const ArRangeDevice **  rangeDevice = NULL,
bool  useLocationDependentDevices = true
const
 

Goes through all the range devices and checks them.

Find the closest reading from any range device's set of current readings within a polar region or "slice" defined by the given angle range. This function iterates through each registered range device (see addRangeDevice()), calls ArRangeDevice::lockDevice(), uses ArRangeDevice::currentReadingPolar() to find a reading, then calls ArRangeDevice::unlockDevice().

The closest reading within a polar region or "slice" defined by the given angle range is returned. Optionally, the specific angle of the found may be placed in angle, if not NULL. The region searched is the region between startAngle, sweeping counter-clockwise to endAngle (0 is straight ahead of the device, -90 to the right, 90 to the left). Note that therefore there is a difference between e.g. the regions (0, 10) and (10, 0). (0, 10) is a 10-degree span near the front of the device, while (10, 0) is a 350 degree span covering the sides and rear. Similarly, (-60, -30) covers 30 degrees on the right hand side, while (-30, -60) covers 330 degrees. (-90, 90) is 180 degrees in front. (-180, 180) covers all sides of the robot. In other words, if you want the smallest section between the two angles, ensure that startAngle < endAngle.

Parameters:
startAngle where to start the slice
endAngle where to end the slice, going counterclockwise from startAngle
angle if given, a pointer to a value in which to put the specific angle to the found reading
Returns:
the range to the obstacle (a value >= the maximum range indicates that no reading was detected in the specified region)
Example:
ArRangeDevice_currentReadingPolar.png

This figure illustrates an example range device and the meanings of arguments and return value.

Parameters:
rangeDevice If not null, then a pointer to the ArRangeDevice that provided the returned reading is placed in this variable.

void ArRobot::clearDirectMotion void   ) 
 

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.

See also:
setDirectMotionPrecedenceTime

getDirectMotionPrecedenceTime

bool ArRobot::com unsigned char  command  ) 
 

Sends a command to the robot with no arguments.

Parameters:
command the command number to send
Returns:
whether the command could be sent or not
See also:
ArCommands
Examples:
gpsRobotTaskExample.cpp.

bool ArRobot::com2Bytes unsigned char  command,
char  high,
char  low
 

Sends a command to the robot with two bytes for argument.

Parameters:
command the command number to send
high the high byte to send with the command
low the low byte to send with the command
Returns:
whether the command could be sent or not
See also:
ArCommands
Examples:
gpsExample.cpp.

bool ArRobot::comInt unsigned char  command,
short int  argument
 

Sends a command to the robot with an int for argument.

Parameters:
command the command number to send
argument the integer argument to send with the command
Returns:
whether the command could be sent or not
See also:
ArCommands
Examples:
actsColorFollowingExample.cpp, armExample.cpp, auxSerialExample.cpp, demo.cpp, dpptuExample.cpp, gotoActionExample.cpp, gpsRobotTaskExample.cpp, gyroExample.cpp, joydriveActionExample.cpp, sonyPTZDemo.cpp, triangleDriveToActionExample.cpp, vcc4CameraExample.cpp, and wander.cpp.

bool ArRobot::comStr unsigned char  command,
const char *  argument
 

Sends a command to the robot with a length-prefixed string for argument.

Parameters:
command the command number to send
argument NULL-terminated string to get data from to send with the command; length to send with packet is determined by strlen
Returns:
whether the command could be sent or not
See also:
ArCommands
Examples:
auxSerialExample.cpp.

bool ArRobot::comStrN unsigned char  command,
const char *  str,
int  size
 

Sends a command to the robot with a length-prefixed string for argument.

Sends a length-prefixed string command to the robot, copying 'size' bytes of data from 'str' into the packet.

Parameters:
command the command number to send
str copy data to send from this character array
size length of the string to send; copy this many bytes from 'str'; use this value as the length prefix byte before the sent string. This length must be less than the maximum packet size of 200.
Returns:
whether the command could be sent or not
See also:
ArCommands

void ArRobot::disableMotors  ) 
 

Disables the motors on the robot.

This command disables the motors on the robot, if it is connected.

void ArRobot::disableSonar  ) 
 

Disables the sonar on the robot.

This command disables the sonars on the robot, if it is connected.

bool ArRobot::disconnect void   ) 
 

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.

Returns:
true if not connected to a robot (so no disconnect can happen, but it didn't failed either), also true if the command could be sent to the robot (ie connection hasn't failed)

void ArRobot::enableMotors  ) 
 

Enables the motors on the robot.

This command enables the motors on the robot, if it is connected.

Examples:
actionExample.cpp, gotoActionExample.cpp, gpsRobotTaskExample.cpp, simpleMotionCommands.cpp, teleopActionsExample.cpp, and wander.cpp.

void ArRobot::enableSonar  ) 
 

Enables the sonar on the robot.

This command enables the sonars on the robot, if it is connected.

ArAction * ArRobot::findAction const char *  actionName  ) 
 

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

Parameters:
actionName the name of the action we want to find
Returns:
the action, if found. If not found, NULL
See also:
addAction

remAction(ArAction*)

remAction(const char*)

ArRangeDevice * ArRobot::findRangeDevice const char *  name,
bool  ignoreCase = false
 

Finds a rangeDevice in the robot's list.

Parameters:
name return the first device with this name
ignoreCase true to ignore case, false to pay attention to it
Returns:
if found, a range device with the given name, if not found NULL

const ArRangeDevice * ArRobot::findRangeDevice const char *  name,
bool  ignoreCase = false
const
 

Finds a rangeDevice in the robot's list.

Parameters:
name return the first device with this name
ignoreCase true to ignore case, false to pay attention to it
Returns:
if found, a range device with the given name, if not found NULL
Examples:
actionExample.cpp.

ArSyncTask * ArRobot::findTask ArFunctor functor  ) 
 

Finds a task by functor.

Finds a task by its functor, searching the entire space of tasks

Returns:
NULL if no task with that functor found, otherwise a pointer to the ArSyncTask for the first task found with that functor

ArSyncTask * ArRobot::findTask const char *  name  ) 
 

Finds a task by name.

Finds a task by its name, searching the entire space of tasks

Returns:
NULL if no task of that name found, otherwise a pointer to the ArSyncTask for the first task found with that name

ArSyncTask * ArRobot::findUserTask ArFunctor functor  ) 
 

Finds a user task by functor.

Finds a user task by its functor, searching the entire space of tasks

Returns:
NULL if no user task with that functor found, otherwise a pointer to the ArSyncTask for the first task found with that functor

ArSyncTask * ArRobot::findUserTask const char *  name  ) 
 

Finds a user task by name.

Finds a user task by its name, searching the entire space of tasks

Returns:
NULL if no user task of that name found, otherwise a pointer to the ArSyncTask for the first task found with that name

void ArRobot::forceTryingToMove void   )  [inline]
 

Manually sets the flag that says the robot is trying to move for one cycle.

This is so that things that might move the robot at any time can can make the robot look like it is otherwise in the TryingToMove state, even if no motion is currently being requested. For example, ArNetworking's teleoperation mode forces TryingToMove at all times while active, not just when requesting motion. This method must be called in each task cycle, it is reset at the end of the task cycle (in state reflection stage) to its natural (non-forced) value.

See also:
isTryingToMove()

ArResolver::ActionMap * ArRobot::getActionMap void   ) 
 

Returns the map of actions... don't do this unless you really know what you're doing

double ArRobot::getBatteryVoltage void   )  const [inline]
 

Gets the battery voltage of the robot (normalized to 12 volt system).

This value is averaged over a number of readings, use getBatteryVoltageNow() to get the value most recently received. (Access the number of readings used in the running average with getBatteryVoltageAverageOfNum() and setBatteryVoltageAverageOfNum().)

This is a value normalized to 12 volts, if you want what the actual voltage of the robot is use getRealBatteryVoltage().

See also:
getRealBatteryVoltage()

getBatteryVoltageNow()

Examples:
simpleConnect.cpp, and simpleMotionCommands.cpp.

double ArRobot::getBatteryVoltageNow void   )  const [inline]
 

Gets the instaneous battery voltage.

This is a value normalized to 12 volts, if you want what the actual voltage of the robot is use getRealBatteryVoltage().

See also:
getBatteryVoltage()

getRealBatteryVoltage()

ArRobot::ChargeState ArRobot::getChargeState void   )  const
 

Gets the charge state of the robot (see long docs).

Note that this is only available on robots with an firwmare operating system (ARCOS or uARCS) thats at least newer than July of 2005. It'll just be CHARGING_UNKNOWN on everything else always.

unsigned int ArRobot::getConnectionCycleMultiplier void   )  const
 

Gets the multiplier for how many cycles ArRobot waits when connecting.

Returns:
when the ArRobot is waiting for a connection packet back from a robot, it waits for this multiplier times the cycle time for the packet to come back before it gives up on it... This should be small for normal connections but if doing something over a slow network then you may want to make it larger

int ArRobot::getConnectionTimeoutTime void   )  const
 

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.

double ArRobot::getControl void   )  const [inline]
 

Gets the control heading.

Gets the control heading as an offset from the current heading.

See also:
getTh

unsigned int ArRobot::getCycleTime void   )  const
 

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.

Returns:
the number of milliseconds between cycles

unsigned int ArRobot::getCycleWarningTime void   ) 
 

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.

Returns:
the number of milliseconds between cycles to warn over, 0 means warning is off

unsigned int ArRobot::getCycleWarningTime void   )  const
 

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.

Returns:
the number of milliseconds between cycles to warn over, 0 means warning is off

ArDeviceConnection * ArRobot::getDeviceConnection void   )  const
 

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

Returns:
the deviceConnection used for this robot
See also:
ArDeviceConnection

ArSerialConnection

ArTcpConnection

unsigned int ArRobot::getDirectMotionPrecedenceTime void   )  const
 

Gets the length of time a direct motion command will take precedence over actions, in milliseconds

ArRetFunctor1< double, ArPoseWithTime > * ArRobot::getEncoderCorrectionCallback void   )  const
 

Gets the encoderCorrectionCallback.

This gets the encoderCorrectionCB, see setEncoderCorrectionCallback for details.

Returns:
the callback, or NULL if there isn't one

ArPose ArRobot::getEncoderPose void   )  const [inline]
 

Get the position of the robot according to the last robot SIP, possibly with gyro correction if installed and enabled, but without any transformations applied.

See also:
getPose()

getRawEncoderPose()

int ArRobot::getEncoderPoseInterpPosition ArTime  timeStamp,
ArPose position
[inline]
 

Gets the encoder position the robot was at at the given timestamp.

See also:
ArInterpolation::getPose

ArTransform ArRobot::getEncoderTransform void   )  const
 

Gets the encoder transform.

Returns:
the transform from encoder to global coords

int ArRobot::getIOAnalog int  num  )  const
 

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).

double ArRobot::getIOAnalogVoltage int  num  )  const
 

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.

ArTime ArRobot::getLastOdometryTime void   )  const
 

Gets the time the last odometry was received.

This gets the ArTime that the last odometry was received

Returns:
the time the last odometry was received

ArTime ArRobot::getLastPacketTime void   )  const
 

Gets the time the last packet was received.

This gets the ArTime that the last packet was received at

Returns:
the time the last packet was received

double ArRobot::getLatVel void   )  const [inline]
 

Gets the current lateral velocity of the robot.

Note that this will only be valid if hasLatVel() returns true

long int ArRobot::getLeftEncoder void   ) 
 

Gets packet data from the left encoder.

Note:
You must first start the encoder packet stream by calling requestEncoderPackets() before this function will return encoder values.

int ArRobot::getOdometryDelay void   )  [inline]
 

Gets the delay in odometry readings.

This gets the odometry delay, not that this is just information about what the delay is it doesn't cause anything to happen in this class.

const ArRobotConfigPacketReader * ArRobot::getOrigRobotConfig void   )  const
 

Gets the original robot config packet information.

Returns:
the ArRobotConfigPacketReader taken when this instance got connected to the robot

ArPose ArRobot::getPose void   )  const [inline]
 

Get the current stored global position of the robot.

This position is updated by data reported by the robot as it moves, and may also be changed by other program components, such as a localization process (see moveTo()).

This position is also referred to as the robot's "odometry" or "odometric" pose, since the robot uses its odometry data to determine this pose; but it may also incorporate additional data sources such as an onboard gyro. The term "odometric pose" also distinguishes this position by the fact that its coordinate system may be arbitrary, and seperate from any external coordinate system.

See also:
getEncoderPose()

moveTo()

int ArRobot::getPoseInterpPosition ArTime  timeStamp,
ArPose position
[inline]
 

Gets the position the robot was at at the given timestamp.

See also:
ArInterpolation::getPose

std::list< ArRangeDevice * > * ArRobot::getRangeDeviceList void   ) 
 

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

Returns:
the list of range dvices attached to this robot

ArPose ArRobot::getRawEncoderPose void   )  const [inline]
 

Get the position of the robot according to the last robot SIP only, with no correction by the gyro, other devices or software proceses.

Note:
For the most accurate pose, use getPose() or getEncoderPose(); only use this method if you must have raw encoder pose with no correction.
See also:
getPose()

getEncoderPose()

double ArRobot::getRealBatteryVoltage void   )  const [inline]
 

Gets the real battery voltage of the robot.

This value is averaged over a number of readings, use getRealBatteryVoltageNow() to get the value most recently received. (Access the number of readings used in the running average with getRealBatteryVoltageAverageOfNum() and setRealBatteryVoltageAverageOfNum().)

This is whatever the actual voltage of the robot is, if you want a value normalized to common 12 volts for all robot types use getBatteryVoltage().

If the robot doesn't support a "real" battery voltage, then this method will just return the normal battery voltage (normalized to 12 volt scale). (Most older robots that don't support a real battery voltage have 12 volts batteries anyway.)

double ArRobot::getRealBatteryVoltageNow void   )  const [inline]
 

Gets the instaneous battery voltage.

This is whatever the actual voltage of the robot is, if you want a value normalized to a common 12 volts for all robot types use getBatteryVoltage(). If the robot doesn't support this number the voltage will be less than 0 and you should use getBatteryVoltageNow().

long int ArRobot::getRightEncoder void   ) 
 

Gets packet data from the right encoder.

Note:
You must first start the encoder packet stream by calling requestEncoderPackets() before this function will return encoder values.

const ArRobotParams * ArRobot::getRobotParams void   )  const
 

Gets the parameters the robot is using.

Returns:
the ArRobotParams instance the robot is using for its parameters

double ArRobot::getRotVel void   )  const [inline]
 

Gets the current rotational velocity of the robot.

Note that with new firmware versions (ARCOS as of April 2006 or so) this is the velocity reported by the robot. With older firmware this number is calculated using the difference between the robot's reported wheel velocities multiplied by diffConvFactor from the .p (robot parameter) files.

Examples:
simpleMotionCommands.cpp.

int ArRobot::getSonarRange int  num  )  const
 

Gets the range of the last sonar reading for the given sonar.

Parameters:
num the sonar number to check, should be between 0 and the number of sonar, the function won't fail if a bad number is given, will just return -1
Returns:
-1 if the sonar has never returned a reading, otherwise the sonar range, which is the distance from the physical sonar disc to where the sonar bounced back
See also:
getNumSonar

ArSensorReading * ArRobot::getSonarReading int  num  )  const
 

Returns the sonar reading for the given sonar.

Parameters:
num the sonar number to check, should be between 0 and the number of sonar, the function won't fail if a bad number is given, will just return false
Returns:
NULL if there is no sonar defined for the given number, otherwise it returns a pointer to an instance of the ArSensorReading, note that this class retains ownership, so the instance pointed to should not be deleted and no pointers to it should be stored. Note that often there will be sonar defined but no readings for it (since the readings may be created by the parameter reader), if there has never been a reading from the sonar then the range of that sonar will be -1 and its counterTaken value will be 0

int ArRobot::getStabilizingTime void   )  const
 

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).

int ArRobot::getStallValue void   )  const [inline]
 

Gets the 2 bytes of stall and bumper flags from the robot.

See robot operations manual SIP packet documentation for details.

See also:
isLeftMotorStalled()

isRightMotorStalled()

int ArRobot::getStateReflectionRefreshTime void   )  const
 

Sets the number of milliseconds between state reflection refreshes if the state has not changed

ArSyncTask * ArRobot::getSyncTaskRoot void   ) 
 

This gets the root of the syncronous task tree, only serious developers should use it

double ArRobot::getTh void   )  const [inline]
 

Gets the global angular position ("theta") of the robot.

See also:
getPose()
Examples:
simpleConnect.cpp, and simpleMotionCommands.cpp.

ArTransform ArRobot::getToGlobalTransform void   )  const
 

This gets the transform from local coords to global coords.

Returns:
an ArTransform which can be used for transforming a position in local coordinates to one in global coordinates

ArTransform ArRobot::getToLocalTransform void   )  const
 

This gets the transform for going from global coords to local coords.

Returns:
an ArTransform which can be used for transforming a position in global coordinates to one in local coordinates

double ArRobot::getX void   )  const [inline]
 

Gets the global X position of the robot.

See also:
getPose()
Examples:
simpleConnect.cpp, and simpleMotionCommands.cpp.

double ArRobot::getY void   )  const [inline]
 

Gets the global Y position of the robot.

See also:
getPose()
Examples:
simpleConnect.cpp, and simpleMotionCommands.cpp.

bool ArRobot::handlePacket ArRobotPacket packet  ) 
 

Internal function, takes a packet and passes it to the packet handlers, returns true if handled, false otherwise

bool ArRobot::hasRangeDevice ArRangeDevice device  )  const
 

Finds whether a particular range device is attached to this robot or not.

Parameters:
device the device to check for

void ArRobot::init void   ) 
 

Internal function, shouldn't be used.

Sets up the packet handlers, sets up the sync list and makes the default priority resolver.

bool ArRobot::isConnected void   )  const [inline]
 

Questions whether the robot is connected or not.

Returns:
true if connected to a robot, false if not

bool ArRobot::isDirectMotion void   )  const
 

Returns true if direct motion commands are blocking actions.

Returns the state of direct motion commands: whether actions are allowed or not

See also:
clearDirectMotion

bool ArRobot::isHeadingDone double  delta = 0.0  )  const
 

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 used is that which was set with setHeadingDoneDiff() (you can get that distnace value with getHeadingDoneDiff(), the default is 3).

Parameters:
delta how close to the goal distance the robot must be
Returns:
true if the robot has achieved the heading given in a move command or if the robot is no longer in heading mode mode (because its now running off of actions, setDHeading(), or setRotVel() was called).
Examples:
directMotionExample.cpp.

bool ArRobot::isMoveDone double  delta = 0.0  ) 
 

Sees if the robot is done moving the previously given move.

Determines if a move command is finished, to within a small distance threshold, "delta". If delta = 0 (default), the delta distance set with setMoveDoneDist() will be used.

Parameters:
delta how close to the goal distance the robot must be, or 0 for previously set default
Returns:
true if the robot has finished the distance given in a move command or if the robot is no longer in a move mode (because its now running off of actions, or setVel() or setVel2() was called).
See also:
setMoveDoneDist

getMoveDoneDist

Examples:
directMotionExample.cpp.

bool ArRobot::isRunning void   )  const
 

Returns whether the robot is currently running or not.

Returns:
true if the robot is currently running in a run or runAsync, otherwise false

bool ArRobot::isSonarNew int  num  )  const
 

Find out if the given sonar reading was newly refreshed by the last incoming SIP received.

Parameters:
num the sonar number to check, should be between 0 and the number of sonar, the function won't fail if a bad number is given, will just return false
Returns:
false if the sonar reading is old, or if there was no reading from that sonar, in the current SIP cycle. For best results, use this function in sync with the SIP cycle, for example, from a Sensor Interpretation Task Callback (see addSensorInterpTask).

bool ArRobot::isTryingToMove void   )  [inline]
 

Gets if the robot is trying to move or not.

"Trying" to move means that some action or other command has requested motion, but another action or factor has cancelled that request.

This is so that if the robot is trying to move, but is prevented (mainly by an action) there'll still be some indication that the robot is trying to move (e.g. we can prevent the sonar from automatically being turned off). Note that this flag doesn't have anything to do with if the robot is really moving or not, to check that, check the current velocities.

See also:
forceTryingToMove() to force this state on

bool ArRobot::loadParamFile const char *  file  ) 
 

Loads a parameter file (replacing all other params).

Returns:
true if the file could be loaded, false otherwise

void ArRobot::logAllTasks void   )  const
 

Logs the list of all tasks, strictly for your viewing pleasure.

See also:
ArLog

void ArRobot::logUserTasks void   )  const
 

Logs the list of user tasks, strictly for your viewing pleasure.

See also:
ArLog

void ArRobot::loopOnce void   ) 
 

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.

void ArRobot::move double  distance  ) 
 

Move the given distance forward/backwards.

Tells the robot to begin moving the specified distance forward/backwards. ArRobot caches this value, and sends it during the next cycle (with a MOVE or VEL command, depending on the robot).

Parameters:
distance the distance for the robot to move (millimeters). Note, due to the implementation of the MOVE command on some robots, it is best to restrict the distance to the range (5000mm, 5000mm] if possible. Not all robots have this restriction, however.
Examples:
directMotionExample.cpp.

void ArRobot::moveTo ArPose  poseTo,
ArPose  poseFrom,
bool  doCumulative = true
 

Change stored pose (i.e. the value returned by getPose()).

The robot-relative positions of the readings of attached range devices, plus sonar readings stored in this object, will also be updated. This variant allows you to manually specify a pose to use as the robot's old pose when updating range device readings (rather than ArRobot's currently stored pose).

Note:
This simply changes our stored pose value, it does not cause the robot to drive. Use setVel(), setRotVel(), move(), setHeading(), setDeltaHeading(), or the actions system.
Parameters:
poseTo the new absolute real world position
poseFrom the original absolute real world position
doCumulative whether to update the cumulative buffers of range devices

void ArRobot::moveTo ArPose  pose,
bool  doCumulative = true
 

Change stored pose (i.e. the value returned by getPose()).

The robot-relative positions of the readings of attached range devices, plus sonar readings stored in this object, will also be updated.

Note:
This simply changes our stored pose value, it does not cause the robot to drive. Use setVel(), setRotVel(), move(), setHeading(), setDeltaHeading(), or the actions system.
Parameters:
pose New pose to set (in absolute world coordinates)
doCumulative whether to update the cumulative buffers of range devices

void ArRobot::packetHandler void   ) 
 

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.

See also:
addPacketHandler

remPacketHandler

bool ArRobot::processMotorPacket ArRobotPacket packet  ) 
 

Processes a motor packet, internal.

MPL adding this so that each place the pose interpolation is used it doesn't have to account for the odometry delay

void ArRobot::processNewSonar char  number,
int  range,
ArTime  timeReceived
 

Processes a new sonar reading, internal.

This function used to just create more sonar readings if it didn't have the sonar number that was given (only the case if that sonar didn't have an entry in the param file), this caused some silent bugs in other peoples code and so was removed... especially since we don't know where the sonar are at if they weren't in the parameter file anyways.

bool ArRobot::remAction const char *  actionName  ) 
 

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

Parameters:
actionName the name of the action we want to find
Returns:
whether remAction found anything with that action to remove or not
See also:
addAction()

remAction(ArAction*)

findAction(const char*)

bool ArRobot::remAction ArAction action  ) 
 

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

Parameters:
action the action we want to remove
Returns:
whether remAction found anything with that action to remove or not
See also:
addAction

remAction(const char*)

findAction(const char*)

void ArRobot::remConnectCB ArFunctor functor  ) 
 

Removes a connect callback.

Parameters:
functor the functor to remove from the list of connect callbacks
See also:
addConnectCB

void ArRobot::remDisconnectNormallyCB ArFunctor functor  ) 
 

Removes a callback for when disconnect is called while connected.

Parameters:
functor the functor to remove from the list of connect callbacks
See also:
addDisconnectNormallyCB

void ArRobot::remDisconnectOnErrorCB ArFunctor functor  ) 
 

Removes a callback for when disconnection happens because of an error.

Parameters:
functor the functor to remove from the list of connect callbacks
See also:
addDisconnectOnErrorCB

void ArRobot::remFailedConnectCB ArFunctor functor  ) 
 

Removes a callback for when a connection to the robot is failed.

Parameters:
functor the functor to remove from the list of connect callbacks
See also:
addFailedConnectCB

void ArRobot::remPacketHandler ArRetFunctor1< bool, ArRobotPacket * > *  functor  ) 
 

Removes a packet handler from the list of packet handlers.

Parameters:
functor the functor to remove from the list of packet handlers
See also:
addPacketHandler

void ArRobot::remRangeDevice ArRangeDevice device  ) 
 

Remove a range device from the robot's list, by instance.

Parameters:
device remove the first device with this pointer value

void ArRobot::remRangeDevice const char *  name  ) 
 

Remove a range device from the robot's list, by name.

Parameters:
name remove the first device with this name

void ArRobot::remRunExitCB ArFunctor functor  ) 
 

Removes a callback for when the run loop exits for what ever reason.

Parameters:
functor The functor to remove from the list of run exit callbacks
See also:
addRunExitCB

void ArRobot::remSensorInterpTask ArFunctor functor  ) 
 

Removes a sensor interp tasks by functor.

See also:
addSensorInterpTask

remSensorInterpTask(std::string name)

void ArRobot::remSensorInterpTask const char *  name  ) 
 

Removes a sensor interp tasks by name.

See also:
addSensorInterpTask

remSensorInterpTask(ArFunctor *functor)

void ArRobot::remStabilizingCB ArFunctor functor  ) 
 

Removes stabilizing callback.

Parameters:
functor the functor to remove from the list of stabilizing callbacks
See also:
addConnectCB

void ArRobot::remUserTask ArFunctor functor  ) 
 

Removes a user task from the list of synchronous taskes by functor.

See also:
addUserTask

remUserTask(std::string name)

void ArRobot::remUserTask const char *  name  ) 
 

Removes a user task from the list of synchronous taskes by name.

See also:
addUserTask

remUserTask(ArFunctor *functor)

void ArRobot::requestEncoderPackets void   ) 
 

Starts a continuous stream of encoder packets.

Encoder packet data may then be from getLeftEncoder(), getRightEncoder().

Encoder packets may be stopped with stopEncoderPackets().

void ArRobot::run bool  stopRunIfNotConnected  ) 
 

Starts the instance to do processing in this thread.

This starts the ongoing main loop, which invokes robot tasks until stopped. This function does not return until the loop is stopped by a call to stopRunning(), or if 'true' is given for stopRunIfNotConnected, and the robot connection is closed or fails.

Parameters:
stopRunIfNotConnected if true, the run will return if there is no connection to the robot at any given point, this is good for one-shot programs... if it is false the run won't return unless stop is called on the instance
See also:
stopRunning()
Examples:
actionExample.cpp, actsColorFollowingExample.cpp, dpptuExample.cpp, gyroExample.cpp, joydriveActionExample.cpp, sonyPTZDemo.cpp, teleopActionsExample.cpp, and vcc4CameraExample.cpp.

void ArRobot::runAsync bool  stopRunIfNotConnected  ) 
 

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

Parameters:
stopRunIfNotConnected if true, the run will stop if there is no connection to the robot at any given point, this is good for one-shot programs... if it is false the run won't stop unless stop is called on the instance
See also:
stopRunning()

waitForRunExit()

lock()

unlock()

Examples:
armExample.cpp, demo.cpp, directMotionExample.cpp, gotoActionExample.cpp, gpsExample.cpp, gpsRobotTaskExample.cpp, lineFinderExample.cpp, moduleExample.cpp, robotConnectionCallbacks.cpp, simpleConnect.cpp, simpleMotionCommands.cpp, triangleDriveToActionExample.cpp, and wander.cpp.

bool ArRobot::setAbsoluteMaxLatAccel double  maxAccel  ) 
 

Sets the robot's absolute maximum lateral acceleration.

This sets the absolute maximum lateral acceleration the robot will do... the acceleration can also be set by the actions and by setLatAccel, 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 setLatAccel.

Parameters:
maxAccel the maximum acceleration to be set, it must be a non-zero number
Returns:
true if the value is good, false othrewise

bool ArRobot::setAbsoluteMaxLatDecel double  maxDecel  ) 
 

Sets the robot's absolute maximum lateral deceleration.

This sets the absolute maximum lateral deceleration the robot will do... the deceleration can also be set by the actions and by setLatDecel, 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 setLatDecel.

Parameters:
maxDecel the maximum deceleration to be set, it must be a non-zero number
Returns:
true if the value is good, false othrewise

bool ArRobot::setAbsoluteMaxLatVel double  maxLatVel  ) 
 

Sets the robot's absolute maximum lateral velocity.

This sets the absolute maximum lateral velocity the robot will go... the maximum velocity can also be set by the actions and by setLatVelMax, 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 setLatVelMax.

Parameters:
maxLatVel the maximum velocity to be set, it must be a non-zero number
Returns:
true if the value is good, false othrewise

bool ArRobot::setAbsoluteMaxRotAccel double  maxAccel  ) 
 

Sets the robot's absolute maximum rotational acceleration.

This sets the absolute maximum rotational acceleration the robot will do... the acceleration can also be set by the actions and by setRotAccel, 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 setRotAccel.

Parameters:
maxAccel the maximum acceleration to be set, it must be a non-zero number
Returns:
true if the value is good, false othrewise

bool ArRobot::setAbsoluteMaxRotDecel double  maxDecel  ) 
 

Sets the robot's absolute maximum rotational deceleration.

This sets the absolute maximum rotational deceleration the robot will do... the deceleration can also be set by the actions and by setRotDecel, 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 setRotDecel.

Parameters:
maxDecel the maximum deceleration to be set, it must be a non-zero number
Returns:
true if the value is good, false othrewise

bool ArRobot::setAbsoluteMaxRotVel double  maxVel  ) 
 

Sets the robot's 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.

Parameters:
maxVel the maximum velocity to be set, it must be a non-zero number
Returns:
true if the value is good, false othrewise

bool ArRobot::setAbsoluteMaxTransAccel double  maxAccel  ) 
 

Sets the robot's absolute maximum translational acceleration.

This sets the absolute maximum translational acceleration the robot will do... the acceleration can also be set by the actions and by setTransAccel, 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 setTransAccel.

Parameters:
maxAccel the maximum acceleration to be set, it must be a non-zero number
Returns:
true if the value is good, false othrewise

bool ArRobot::setAbsoluteMaxTransDecel double  maxDecel  ) 
 

Sets the robot's absolute maximum translational deceleration.

This sets the absolute maximum translational deceleration the robot will do... the deceleration can also be set by the actions and by setTransDecel, 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 setTransDecel.

Parameters:
maxDecel the maximum deceleration to be set, it must be a non-zero number
Returns:
true if the value is good, false othrewise

bool ArRobot::setAbsoluteMaxTransVel double  maxVel  ) 
 

Sets the robot's 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.

Parameters:
maxVel the maximum velocity to be set, it must be a non-zero number
Returns:
true if the value is good, false othrewise
Examples:
actsColorFollowingExample.cpp, and teleopActionsExample.cpp.

void ArRobot::setConnectionCycleMultiplier unsigned int  multiplier  ) 
 

Sets the multiplier for how many cycles ArRobot waits when connecting.

Parameters:
multiplier when the ArRobot is waiting for a connection packet back from a robot, it waits for this multiplier times the cycle time for the packet to come back before it gives up on it... This should be small for normal connections but if doing something over a slow network then you may want to make it larger

void ArRobot::setConnectionTimeoutTime int  mSecs  ) 
 

Sets the time without a response until connection assumed lost.

Sets the number of milliseconds 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.

Parameters:
mSecs if seconds is 0 then the connection timeout feature will be disabled, otherwise disconnect on error will be triggered after this number of seconds...

void ArRobot::setCycleTime unsigned int  ms  ) 
 

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.

Parameters:
ms the number of milliseconds between cycles

void ArRobot::setCycleWarningTime unsigned int  ms  ) 
 

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.

Parameters:
ms the number of milliseconds between cycles to warn over, 0 turns warning off

void ArRobot::setDeadReconPose ArPose  pose  ) 
 

Sets the dead recon position of the robot.

Parameters:
pose the position to set the dead recon position to

void ArRobot::setDeltaHeading double  deltaHeading  ) 
 

Sets the delta heading.

Sets a delta heading to the robot, it caches this value, and sends it during the next cycle.

Parameters:
deltaHeading the desired amount to change the heading of the robot by
Examples:
directMotionExample.cpp.

void ArRobot::setDeviceConnection ArDeviceConnection connection  ) 
 

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

Parameters:
connection The deviceConnection to use for this robot
See also:
ArDeviceConnection, ArSerialConnection, ArTcpConnection
Examples:
sonyPTZDemo.cpp, and vcc4CameraExample.cpp.

void ArRobot::setDirectMotionPrecedenceTime int  mSec  ) 
 

Sets the length of time a direct motion command will take precedence over actions, in milliseconds

void ArRobot::setEncoderCorrectionCallback ArRetFunctor1< double, ArPoseWithTime > *  functor  ) 
 

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.

Parameters:
functor an ArRetFunctor1 created as an ArRetFunctor1C, that will be the callback... call this function NULL to clear the callback
See also:
getEncoderCorrectionCallback

void ArRobot::setEncoderTransform ArPose  transformPos  ) 
 

Changes the transform directly.

This transform is applied to all odometric/encoder poses received. If you simply want to transform the robot's final reported pose (as returned by getPose()) to match an external coordinate system, use moveTo() instead.

See also:
moveTo()
Parameters:
transformPos the position to transform to

void ArRobot::setEncoderTransform ArPose  deadReconPos,
ArPose  globalPos
 

Changes the transform.

This transform is applied to all odometric/encoder poses received. If you simply want to transform the robot's final reported pose (as returned by getPose()) to match an external coordinate system, use moveTo() instead.

See also:
moveTo()
Parameters:
deadReconPos the dead recon position to transform from
globalPos the real world global position to transform to

void ArRobot::setHeading double  heading  ) 
 

Sets the heading.

Sets the heading of the robot, it caches this value, and sends it during the next cycle.

Parameters:
heading the desired heading of the robot (degrees)
Examples:
directMotionExample.cpp, and gyroExample.cpp.

void ArRobot::setLatVel double  latVelocity  ) 
 

Sets the lateral velocity

See also:
clearDirectMotion

void ArRobot::setOdometryDelay int  msec  )  [inline]
 

Sets the delay in the odometry readings.

Note that this doesn't cause a delay, its informational so that the delay can be adjusted for and causes nothing to happen in this class.

void ArRobot::setRobotParams ArRobotParams params  ) 
 

Sets the robot to use a passed in set of params (passes ownership).

This function will take over ownership of the passed in params

void ArRobot::setRotVel double  velocity  ) 
 

Sets the rotational velocity.

Sets the rotational velocity of the robot, it caches this value, and sends it during the next cycle.

Parameters:
velocity the desired rotational velocity of the robot (deg/sec)
Examples:
directMotionExample.cpp, gyroExample.cpp, and simpleMotionCommands.cpp.

void ArRobot::setStabilizingTime int  mSecs  ) 
 

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.

Parameters:
mSecs the amount of time to stabilize for (0 disables)
See also:
addStabilizingCB

void ArRobot::setStateReflectionRefreshTime int  msec  ) 
 

Sets the number of milliseconds between state reflection refreshes if the state has not changed

void ArRobot::setVel double  velocity  ) 
 

Sets the velocity

See also:
clearDirectMotion
Examples:
directMotionExample.cpp, and simpleMotionCommands.cpp.

void ArRobot::setVel2 double  leftVelocity,
double  rightVelocity
 

Sets the velocity of the wheels independently.

Sets the velocity of each of the wheels on the robot independently. ArRobot caches these values, and sends them with a VEL2 command 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.

See also:
setVel

setRotVel

clearDirectMotion

Parameters:
leftVelocity the desired velocity of the left wheel
rightVelocity the desired velocity of the right wheel
Examples:
directMotionExample.cpp.

void ArRobot::stateReflector void   ) 
 

State Reflector, internal.

MPL commenting out these lines, and making it so that if nothing is set it'll just stop

void ArRobot::stop void   ) 
 

Stops the robot

See also:
clearDirectMotion
Examples:
directMotionExample.cpp, and simpleMotionCommands.cpp.

void ArRobot::stopRunning bool  doDisconnect = true  ) 
 

Stops the robot from doing any more processing.

This stops this robot's processing cycle. If it is running in a background thread (from runAsync()), it will cause that thread to exit. If it is running synchronously (from run()), then run() will return.

Parameters:
doDisconnect If true, also disconnect from the robot connection (default is true).
See also:
isRunning
Examples:
robotConnectionCallbacks.cpp, simpleConnect.cpp, and simpleMotionCommands.cpp.

void ArRobot::stopStateReflection void   ) 
 

Sets the state reflection to be inactive (until motion or clearDirectMotion)

See also:
clearDirectMotion

ArRobot::WaitState ArRobot::waitForConnect unsigned int  msecs = 0  ) 
 

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().

Parameters:
msecs milliseconds in which to wait for the ArRobot to connect
Returns:
WAIT_CONNECTED for success
See also:
waitForConnectOrConnFail

wakeAllWaitingThreads

wakeAllConnWaitingThreads

wakeAllRunExitWaitingThreads

ArRobot::WaitState ArRobot::waitForConnectOrConnFail unsigned int  msecs = 0  ) 
 

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.

Parameters:
msecs milliseconds in which to wait for the ArRobot to connect
Returns:
WAIT_CONNECTED for success
See also:
waitForConnect

ArRobot::WaitState ArRobot::waitForRunExit unsigned int  msecs = 0  ) 
 

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.

Parameters:
msecs milliseconds in which to wait for the robot to connect
Returns:
WAIT_RUN_EXIT for success
Examples:
demo.cpp, lineFinderExample.cpp, simpleConnect.cpp, simpleMotionCommands.cpp, triangleDriveToActionExample.cpp, and wander.cpp.

void ArRobot::wakeAllConnOrFailWaitingThreads  ) 
 

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.

See also:
wakeAllWaitingThreads

wakeAllRunExitWaitingThreads

void ArRobot::wakeAllConnWaitingThreads  ) 
 

Wake up all threads waiting for connection.

This will wake all the threads waiting for the robot to be connected.

See also:
wakeAllWaitingThreads

wakeAllRunExitWaitingThreads

void ArRobot::wakeAllRunExitWaitingThreads  ) 
 

Wake up all threads waiting for the run loop to exit.

This will wake all the threads waiting for the run loop to exit.

See also:
wakeAllWaitingThreads

wakeAllConnWaitingThreads

void ArRobot::wakeAllWaitingThreads  ) 
 

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.

See also:
wakeAllConnWaitingThreads

wakeAllRunExitWaitingThreads


The documentation for this class was generated from the following files:
Generated on Thu Jan 7 10:34:44 2010 for Aria by  doxygen 1.4.2