#include <ArRobot.h>
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.
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. | |
ArAction * | findAction (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. | |
ArLaser * | findLaser (int laserNumber) |
Finds a laser in the robot's list. | |
const ArLaser * | findLaser (int laserNumber) const |
Finds a laser in the robot's list. | |
ArRangeDevice * | findRangeDevice (const char *name, bool ignoreCase=false) |
Finds a rangeDevice in the robot's list. | |
const ArRangeDevice * | findRangeDevice (const char *name, bool ignoreCase=false) const |
Finds a rangeDevice in the robot's list. | |
ArSyncTask * | findTask (ArFunctor *functor) |
Finds a task by functor. | |
ArSyncTask * | findTask (const char *name) |
Finds a task by name. | |
ArSyncTask * | findUserTask (ArFunctor *functor) |
Finds a user task by functor. | |
ArSyncTask * | findUserTask (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::ActionMap * | getActionMap (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. | |
ArDeviceConnection * | getDeviceConnection (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. | |
ArKeyHandler * | getKeyHandler (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 ArRobotConfigPacketReader * | getOrigRobotConfig (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. | |
ArPTZ * | getPTZ (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. | |
ArResolver * | getResolver (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 ArRobotParams * | getRobotParams (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. | |
ArSensorReading * | getSonarReading (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 |
ArSyncTask * | getSyncTaskRoot (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< ArRobot > | myActionHandlerCB |
ArRetFunctor1C< bool, ArRobot, ArRobotPacket * > | myEncoderPacketCB |
ArRetFunctorC< unsigned int, ArRobot > | myGetCycleWarningTimeCB |
ArRetFunctorC< bool, ArRobot > | myGetNoTimeWarningThisCycleCB |
ArRetFunctor1C< bool, ArRobot, ArRobotPacket * > | myIOPacketCB |
ArFunctorC< ArKeyHandler > * | myKeyHandlerCB |
ArFunctorC< ArRobot > | myKeyHandlerExitCB |
ArRetFunctor1C< bool, ArRobot, ArRobotPacket * > | myMotorPacketCB |
ArFunctorC< ArRobot > | myPacketHandlerCB |
ArFunctorC< ArRobot > | myRobotLockerCB |
ArFunctorC< ArRobot > | myRobotUnlockerCB |
ArFunctorC< ArRobot > | myStateReflectorCB |
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< ArRobot > | myAriaExitCB |
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 |
ArDeviceConnection * | myConn |
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 |
ArKeyHandler * | myKeyHandler |
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 |
ArRobotConfigPacketReader * | myOrigRobotConfig |
bool | myOverriddenChargeState |
bool | myOwnTheResolver |
std::list< ArRetFunctor1< bool, ArRobotPacket * > * > | myPacketHandlerList |
bool | myPacketsReceivedTracking |
long | myPacketsReceivedTrackingCount |
ArTime | myPacketsReceivedTrackingStarted |
bool | myPacketsSentTracking |
ArRobotParams * | myParams |
ArPTZ * | myPtz |
std::list< ArRangeDevice * > | myRangeDeviceList |
ArPoseWithTime | myRawEncoderPose |
ArRunningAverage | myRealBatteryAverager |
double | myRealBatteryVoltage |
ArRobotPacketReceiver | myReceiver |
bool | myRequestedEncoderPackets |
bool | myRequestedIOPackets |
ArResolver * | myResolver |
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 |
ArSyncTask * | mySyncTaskRoot |
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 |
enum ArRobot::WaitState |
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.
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().
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().
double ArRobot::getControl | ( | void | ) | const [inline] |
Gets the control heading.
Gets the control heading as an offset from the current heading.
unsigned int ArRobot::getDirectMotionPrecedenceTime | ( | void | ) | const |
Gets the length of time a direct motion command will take precedence over actions, in milliseconds
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.
Gets the encoder position the robot was at at the given timestamp.
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
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.
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.
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.
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().
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.
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.
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] |
double ArRobot::getX | ( | void | ) | const [inline] |
double ArRobot::getY | ( | void | ) | const [inline] |
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::isConnected | ( | void | ) | const [inline] |
Questions whether the robot is connected or not.
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.
void ArRobot::setDirectMotionPrecedenceTime | ( | int | mSec | ) |
Sets the length of time a direct motion command will take precedence over actions, in milliseconds
void ArRobot::setLatVel | ( | double | latVelocity | ) |
Sets the lateral velocity
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::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
void ArRobot::stop | ( | void | ) |
Stops the robot
void ArRobot::stopStateReflection | ( | void | ) |
Sets the state reflection to be inactive (until motion or clearDirectMotion)