#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.
actionExample.cpp, actionGroupExample.cpp, actsColorFollowingExample.cpp, armExample.cpp, auxSerialExample.cpp, demo.cpp, dpptuExample.cpp, gotoActionExample.cpp, gripperExample.cpp, gyroExample.cpp, joydriveActionExample.cpp, lineFinderExample.cpp, moduleExample.cpp, moduleExample_Mod.cpp, robotConnectionCallbacks.cpp, robotSyncTaskExample.cpp, simpleConnect.cpp, sonyPTZDemo.cpp, teleopActionsExample.cpp, triangleDriveToActionExample.cpp, vcc4CameraExample.cpp, and wander.cpp.
Definition at line 73 of file ArRobot.h.
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. | |
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 distance to a point from the robot. | |
double | findDeltaHeadingTo (const ArPose pose) |
Gets the distance to a point from the robot. | |
double | findDistanceTo (const ArPose pose) |
Gets the distance to a point from the robot. | |
ArRangeDevice * | findRangeDevice (const char *name) |
Finds a rangeDevice in the robot's list. | |
const ArRangeDevice * | findRangeDevice (const char *name) 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) |
Sets the flag that says the robot is trying to move. | |
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 |
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. | |
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. | |
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. | |
ArTime | getLastPacketTime (void) const |
Gets the time the last packet was received. | |
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 odometer was reset (sec). | |
int | getOdometryDelay (void) |
Gets the delay in odometry readings. | |
const ArRobotConfigPacketReader * | getOrigRobotConfig (void) const |
Gets the original robot config packet information. | |
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. This pose 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()). | |
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 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 (see operations manual for details). | |
int | getStateReflectionRefreshTime (void) const |
ArSyncTask * | getSyncTaskRoot (void) |
double | getTh (void) const |
Gets the global Th location 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 | getVel (void) const |
Gets the translational velocity of the robot. | |
double | getX (void) const |
Gets the global X location of the robot. | |
double | getY (void) const |
Gets the global Y location of the robot. | |
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 | 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). | |
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. | |
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 | resetOdometer (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 | 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 | 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 | 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 | |
void | setLogActions (bool logActions) |
Sets if we're logging all the movement commands sent down. | |
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 | 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 received (just times and types). | |
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 | 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 | 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 | 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 | myAbsoluteMaxRotAccel |
double | myAbsoluteMaxRotDecel |
double | myAbsoluteMaxRotVel |
double | myAbsoluteMaxTransAccel |
double | myAbsoluteMaxTransDecel |
double | myAbsoluteMaxTransVel |
ArActionDesired | myActionDesired |
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 |
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 |
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 |
bool | myLastActionRotHeading |
bool | myLastActionRotStopped |
int | myLastActionRotVal |
int | myLastActionTransVal |
double | myLastCalculatedRotVel |
double | myLastHeading |
ArTime | myLastIOPacketReceivedTime |
ArTime | myLastPacketReceivedTime |
ArTime | myLastPulseSent |
ArTime | myLastRotSent |
RotDesired | myLastRotType |
int | myLastRotVal |
double | myLastRotVel |
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 |
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 | 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 |
int | myStateReflectionRefreshTime |
ArSyncLoop | mySyncLoop |
ArSyncTask * | mySyncTaskRoot |
time_t | myTimeLastMotorPacket |
time_t | myTimeLastSonarPacket |
int | myTimeoutTime |
double | myTransAccel |
double | myTransDecel |
ArPose | myTransDistStart |
ArTime | myTransSetTime |
TransDesired | myTransType |
double | myTransVal |
double | myTransVal2 |
double | myTransVelMax |
bool | myTryingToMove |
double | myVel |
bool | myWarnedAboutExtraSonar |
|
|
|
Constructor. The parameters only rarely need to be specified.
Definition at line 69 of file ArRobot.cpp. |
|
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. Definition at line 3436 of file ArRobot.cpp. |
|
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.
Definition at line 2493 of file ArRobot.cpp. |
|
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.
Definition at line 1866 of file ArRobot.cpp. |
|
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.
Definition at line 1933 of file ArRobot.cpp. |
|
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.
Definition at line 1970 of file ArRobot.cpp. |
|
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.
Definition at line 1901 of file ArRobot.cpp. |
|
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.
Definition at line 1833 of file ArRobot.cpp. |
|
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.
Definition at line 2002 of file ArRobot.cpp. |
|
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).
Definition at line 2316 of file ArRobot.cpp. |
|
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).
Definition at line 2034 of file ArRobot.cpp. |
|
Adds a user task to the list of synchronous taskes. The synchronous tasks get called every robot cycle (every 100 ms by default).
Definition at line 2238 of file ArRobot.cpp. |
|
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
Definition at line 4716 of file ArRobot.cpp. |
|
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).
Definition at line 577 of file ArRobot.cpp. |
|
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.
Definition at line 651 of file ArRobot.cpp. |
|
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.
Definition at line 4960 of file ArRobot.cpp. |
|
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).
Definition at line 618 of file ArRobot.cpp. |
|
This goes through all of the registered range devices and locks each, calls cumulativeReadingBox on it, and then unlocks it. Gets the closest reading in a region defined by the two points of a rectangle.
Definition at line 4492 of file ArRobot.cpp. |
|
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.
![]() This figure illustrates an example range device and the meanings of arguments and return value.
Definition at line 4359 of file ArRobot.cpp. |
|
This goes through all of the registered range devices and locks each, calls currentReadingBox on it, and then unlocks it. Gets the closest reading in a region defined by the two points of a rectangle.
Definition at line 4426 of file ArRobot.cpp. |
|
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.
![]() This figure illustrates an example range device and the meanings of arguments and return value.
Definition at line 4295 of file ArRobot.cpp. |
|
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. Definition at line 4844 of file ArRobot.cpp. |
|
Sends a command to the robot with no arguments.
Definition at line 4048 of file ArRobot.cpp. |
|
Sends a command to the robot with two bytes for argument.
Definition at line 4075 of file ArRobot.cpp. |
|
Sends a command to the robot with an int for argument.
Definition at line 4061 of file ArRobot.cpp. |
|
Sends a command to the robot with a length-prefixed string for argument.
Definition at line 4089 of file ArRobot.cpp. |
|
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.
Definition at line 4106 of file ArRobot.cpp. |
|
Disables the motors on the robot. This command disables the motors on the robot, if it is connected. Definition at line 4895 of file ArRobot.cpp. |
|
Disables the sonar on the robot. This command disables the sonars on the robot, if it is connected. Definition at line 4911 of file ArRobot.cpp. |
|
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.
Definition at line 1368 of file ArRobot.cpp. |
|
Enables the motors on the robot. This command enables the motors on the robot, if it is connected.
Definition at line 4887 of file ArRobot.cpp. |
|
Enables the sonar on the robot. This command enables the sonars on the robot, if it is connected. Definition at line 4903 of file ArRobot.cpp. |
|
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
Definition at line 2577 of file ArRobot.cpp. |
|
Finds a rangeDevice in the robot's list.
Definition at line 4220 of file ArRobot.cpp. |
|
Finds a rangeDevice in the robot's list.
Definition at line 4240 of file ArRobot.cpp. |
|
Finds a task by functor. Finds a task by its functor, searching the entire space of tasks
Definition at line 2463 of file ArRobot.cpp. |
|
Finds a task by name. Finds a task by its name, searching the entire space of tasks
Definition at line 2449 of file ArRobot.cpp. |
|
Finds a user task by functor. Finds a user task by its functor, searching the entire space of tasks
Definition at line 2431 of file ArRobot.cpp. |
|
Finds a user task by name. Finds a user task by its name, searching the entire space of tasks
Definition at line 2413 of file ArRobot.cpp. |
|
Sets the flag that says the robot is trying to move. This is so that things that might move can make the robot look like it is trying to move. For example, so teleop mode can say that it might make the robot move, so the sonar aren't turned off
|
|
Returns the map of actions... don't do this unless you really know what you're doing Definition at line 2601 of file ArRobot.cpp. |
|
Gets the battery voltage of the robot (normalized to 12 volt system). This value is averaged over a number of readings, (You can get this number by calling getBatteryVoltageAverageOfNum and set this with setBatteryVoltageAverageOfNum... you can call getBatteryVoltageNow to get the reading from the last packet. This is a value normalized to 12 volts, if you want what the actual voltage of the robot is use getRealBatteryVoltage.
|
|
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. |
|
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. Definition at line 5011 of file ArRobot.cpp. |
|
Gets the multiplier for how many cycles ArRobot waits when connecting.
Definition at line 3575 of file ArRobot.cpp. |
|
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. Definition at line 532 of file ArRobot.cpp. |
|
Gets the control heading. Gets the control heading as an offset from the current heading.
|
|
Gets the number of ms between cycles. Finds the number of milliseconds between cycles, at each cycle is when all packets are processed, all sensors are interpretted, all actions are called, and all user tasks are serviced. Be warned, if you set this too small you could overflow your serial connection.
Definition at line 3548 of file ArRobot.cpp. |
|
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.
Definition at line 3494 of file ArRobot.cpp. |
|
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.
Definition at line 3481 of file ArRobot.cpp. |
|
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
Definition at line 503 of file ArRobot.cpp. |
|
Gets the length of time a direct motion command will take precedence over actions, in milliseconds Definition at line 4832 of file ArRobot.cpp. |
|
Gets the encoderCorrectionCallback. This gets the encoderCorrectionCB, see setEncoderCorrectionCallback for details.
Definition at line 4800 of file ArRobot.cpp. |
|
Get the position of the robot according to the last robot SIP, possibly with gyro correction if installed and enabled.
|
|
Gets the encoder position the robot was at at the given timestamp.
|
|
Gets the encoder transform.
Definition at line 4665 of file ArRobot.cpp. |
|
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). Definition at line 1763 of file ArRobot.cpp. |
|
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. Definition at line 1774 of file ArRobot.cpp. |
|
Gets the time the last packet was received. This gets the ArTime that the last packet was received at
Definition at line 542 of file ArRobot.cpp. |
|
Gets packet data from the left encoder.
Definition at line 3293 of file ArRobot.cpp. |
|
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. |
|
Gets the original robot config packet information.
Definition at line 1812 of file ArRobot.cpp. |
|
Get the current stored global position of the robot. This pose 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()).
|
|
Gets the position the robot was at at the given timestamp.
|
|
Gets the range device list. This gets the list of range devices attached to this robot, do NOT manipulate this list directly. If you want to manipulate use the appropriate addRangeDevice, or remRangeDevice
Definition at line 4262 of file ArRobot.cpp. |
|
Get the position of the robot according to the last robot SIP only, with no correction by the gyro, other devices or software proceses.
|
|
Gets the real battery voltage of the robot. This value is averaged over a number of readings, you can get this by calling getRealBatteryVoltageAverageOfNum and set this with setRealBatteryVoltageAverageOfNum... you can call getRealBatteryVoltageNow to get the reading from the last packet. This is whatever the actual voltage of the robot is, if you want a value normalized to 12 volts use getBatteryVoltage. If the robot connected to doesn't send the real battery voltage it will just use the normal battery voltage (normalized to 12 volt scale). |
|
Gets the instaneous battery voltage. This is whatever the actual voltage of the robot is, if you want a value normalized to 12 volts use getBatteryVoltage. If the robot doesn't support this number the voltage will be less than 0 and you should use getBatteryVoltageNow. |
|
Gets packet data from the right encoder.
Definition at line 3301 of file ArRobot.cpp. |
|
Gets the parameters the robot is using.
Definition at line 1803 of file ArRobot.cpp. |
|
Gets the rotational velocity of the robot. Note that with new firmware versions (as of April 2006 or so) this is the velocity reported by the robot. With older firmware this number is come up with by the difference between the wheel velocities multiplied by diffConvFactor from the .p files. |
|
Gets the range of the last sonar reading for the given sonar.
Definition at line 3990 of file ArRobot.cpp. |
|
Returns the sonar reading for the given sonar.
Definition at line 4032 of file ArRobot.cpp. |
|
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). Definition at line 3536 of file ArRobot.cpp. |
|
Sets the number of milliseconds between state reflection refreshes if the state has not changed Definition at line 4940 of file ArRobot.cpp. |
|
This gets the root of the syncronous task tree, only serious developers should use it Definition at line 2217 of file ArRobot.cpp. |
|
This gets the transform from local coords to global coords.
Definition at line 4685 of file ArRobot.cpp. |
|
This gets the transform for going from global coords to local coords.
Definition at line 4699 of file ArRobot.cpp. |
|
Internal function, takes a packet and passes it to the packet handlers, returns true if handled, false otherwise Definition at line 3256 of file ArRobot.cpp. |
|
Finds whether a particular range device is attached to this robot or not.
Definition at line 4270 of file ArRobot.cpp. |
|
Internal function, shouldn't be used. Sets up the packet handlers, sets up the sync list and makes the default priority resolver. Definition at line 188 of file ArRobot.cpp. |
|
Questions whether the robot is connected or not.
|
|
Returns true if direct motion commands are blocking actions. Returns the state of direct motion commands: whether actions are allowed or not
Definition at line 4874 of file ArRobot.cpp. |
|
Sees if the robot is done changing to the previously given setHeading. Determines if a setHeading() command is finished, to within a small distance. If delta = 0 (default), the delta distance is what was set with setHeadingDoneDiff(), you can get the distnace with getHeadingDoneDiff()
Definition at line 1553 of file ArRobot.cpp. |
|
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.
Definition at line 1528 of file ArRobot.cpp. |
|
Returns whether the robot is currently running or not.
Definition at line 224 of file ArRobot.cpp. |
|
Find out if the given sonar reading was newly refreshed by the last incoming SIP received.
Definition at line 4010 of file ArRobot.cpp. |
|
Gets if the robot is trying to move or not. This is so that if the robot is trying to move, but is prevented (mainly in actions) there'll still be some indication that the robot is trying to move so that things like the sonar aren't turned off because the robot's stopped, note that this flag doesn't have anything to do with if the robot is really moving or not and that you'll still want to check the vels for that
|
|
Loads a parameter file (replacing all other params).
Definition at line 1084 of file ArRobot.cpp. |
|
Logs the list of all tasks, strictly for your viewing pleasure.
Definition at line 2402 of file ArRobot.cpp. |
|
Logs the list of user tasks, strictly for your viewing pleasure.
Definition at line 2386 of file ArRobot.cpp. |
|
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. Definition at line 3587 of file ArRobot.cpp. |
|
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).
Definition at line 1505 of file ArRobot.cpp. |
|
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).
Definition at line 4604 of file ArRobot.cpp. |
|
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.
Definition at line 4554 of file ArRobot.cpp. |
|
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.
Definition at line 3331 of file ArRobot.cpp. |
|
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. Definition at line 3904 of file ArRobot.cpp. |
|
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
Definition at line 2517 of file ArRobot.cpp. |
|
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
Definition at line 2547 of file ArRobot.cpp. |
|
Removes a connect callback.
Definition at line 1882 of file ArRobot.cpp. |
|
Removes a callback for when disconnect is called while connected.
Definition at line 1949 of file ArRobot.cpp. |
|
Removes a callback for when disconnection happens because of an error.
Definition at line 1986 of file ArRobot.cpp. |
|
Removes a callback for when a connection to the robot is failed.
Definition at line 1917 of file ArRobot.cpp. |
|
Removes a packet handler from the list of packet handlers.
Definition at line 1850 of file ArRobot.cpp. |
|
Remove a range device from the robot's list, by instance.
Definition at line 4203 of file ArRobot.cpp. |
|
Remove a range device from the robot's list, by name.
Definition at line 4187 of file ArRobot.cpp. |
|
Removes a callback for when the run loop exits for what ever reason.
Definition at line 2017 of file ArRobot.cpp. |
|
Removes a sensor interp tasks by functor.
Definition at line 2361 of file ArRobot.cpp. |
|
Removes a sensor interp tasks by name.
Definition at line 2336 of file ArRobot.cpp. |
|
Removes stabilizing callback.
Definition at line 2050 of file ArRobot.cpp. |
|
Removes a user task from the list of synchronous taskes by functor.
Definition at line 2283 of file ArRobot.cpp. |
|
Removes a user task from the list of synchronous taskes by name.
Definition at line 2258 of file ArRobot.cpp. |
|
Starts a continuous stream of encoder packets. Encoder packet data may then be from getLeftEncoder(), getRightEncoder(). Encoder packets may be stopped with stopEncoderPackets(). Definition at line 1287 of file ArRobot.cpp. |
|
Starts the instance to do processing in this thread. This starts the list of tasks to be run through until stopped. This function doesn't return until something calls stop on this instance.
Definition at line 206 of file ArRobot.cpp. |
|
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
Definition at line 238 of file ArRobot.cpp. |
|
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.
Definition at line 1726 of file ArRobot.cpp. |
|
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.
Definition at line 1749 of file ArRobot.cpp. |
|
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.
Definition at line 1703 of file ArRobot.cpp. |
|
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.
Definition at line 1659 of file ArRobot.cpp. |
|
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.
Definition at line 1682 of file ArRobot.cpp. |
|
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.
Definition at line 1636 of file ArRobot.cpp. |
|
Sets the multiplier for how many cycles ArRobot waits when connecting.
Definition at line 3563 of file ArRobot.cpp. |
|
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.
Definition at line 518 of file ArRobot.cpp. |
|
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.
Definition at line 3506 of file ArRobot.cpp. |
|
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.
Definition at line 3467 of file ArRobot.cpp. |
|
Sets the dead recon position of the robot.
Definition at line 4673 of file ArRobot.cpp. |
|
Sets the delta heading. Sets a delta heading to the robot, it caches this value, and sends it during the next cycle.
Definition at line 1610 of file ArRobot.cpp. |
|
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
Definition at line 488 of file ArRobot.cpp. |
|
Sets the length of time a direct motion command will take precedence over actions, in milliseconds Definition at line 4815 of file ArRobot.cpp. |
|
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.
Definition at line 4788 of file ArRobot.cpp. |
|
Changes the transform directly.
Definition at line 4656 of file ArRobot.cpp. |
|
Changes the transform.
Definition at line 4646 of file ArRobot.cpp. |
|
Sets the heading. Sets the heading of the robot, it caches this value, and sends it during the next cycle.
Definition at line 1572 of file ArRobot.cpp. |
|
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. |
|
Sets the rotational velocity. Sets the rotational velocity of the robot, it caches this value, and sends it during the next cycle.
Definition at line 1591 of file ArRobot.cpp. |
|
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.
Definition at line 3523 of file ArRobot.cpp. |
|
Sets the number of milliseconds between state reflection refreshes if the state has not changed Definition at line 4925 of file ArRobot.cpp. |
|
Sets the velocity
Definition at line 1463 of file ArRobot.cpp. |
|
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.
Definition at line 1485 of file ArRobot.cpp. |
|
Stops the robot
Definition at line 1446 of file ArRobot.cpp. |
|
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.
Definition at line 260 of file ArRobot.cpp. |
|
Sets the state reflection to be inactive (until motion or clearDirectMotion)
Definition at line 4862 of file ArRobot.cpp. |
|
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().
Definition at line 2076 of file ArRobot.cpp. |
|
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.
Definition at line 2108 of file ArRobot.cpp. |
|
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.
Definition at line 2143 of file ArRobot.cpp. |
|
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. Definition at line 2195 of file ArRobot.cpp. |
|
Wake up all threads waiting for connection. This will wake all the threads waiting for the robot to be connected. Definition at line 2183 of file ArRobot.cpp. |
|
Wake up all threads waiting for the run loop to exit. This will wake all the threads waiting for the run loop to exit. Definition at line 2205 of file ArRobot.cpp. |
|
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. Definition at line 2172 of file ArRobot.cpp. |