Aria
2.8.0
|
Central class for communicating with and operating the robot. More...
#include <ArRobot.h>
Public Types | |
enum | ChargeState { CHARGING_UNKNOWN = -1, CHARGING_NOT = 0, CHARGING_BULK = 1, CHARGING_OVERCHARGE = 2, CHARGING_FLOAT = 3, CHARGING_BALANCE = 4 } |
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. More... | |
bool | addAction (ArAction *action, int priority) |
Adds an action to the list with the given priority. More... | |
bool | addBattery (ArBatteryMTX *battery, int batteryNumber) |
Adds a battery to the robot's map of them. More... | |
void | addConnectCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a connect callback. More... | |
void | addDisconnectNormallyCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a callback for when disconnect is called while connected. More... | |
void | addDisconnectOnErrorCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a callback for when disconnection happens because of an error. More... | |
void | addFailedConnectCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a callback for when a connection to the robot is failed. More... | |
bool | addLaser (ArLaser *laser, int laserNumber, bool addAsRangeDevice=true) |
Adds a laser to the robot's map of them. More... | |
bool | addLCD (ArLCDMTX *lcd, int lcdNumber) |
Adds a lcd to the robot's map of them. More... | |
void | addPacketHandler (ArRetFunctor1< bool, ArRobotPacket *> *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a packet handler to the list of packet handlers. More... | |
void | addRangeDevice (ArRangeDevice *device) |
Adds a rangeDevice to the robot's list of them, and set the ArRangeDevice object's robot pointer to this ArRobot object. More... | |
void | addRunExitCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a callback for when the run loop exits for what ever reason. More... | |
bool | addSensorInterpTask (const char *name, int position, ArFunctor *functor, ArTaskState::State *state=NULL) |
Adds a task under the sensor interp part of the syncronous tasks. More... | |
void | addSetEncoderTransformCB (ArFunctor *functor, int position=50) |
Adds a callback for when the encoder transform is changed. | |
bool | addSonar (ArSonarMTX *sonar, int sonarNumber) |
Adds a sonar to the robot's map of them. More... | |
void | addStabilizingCB (ArFunctor *functor, ArListPos::Pos position=ArListPos::LAST) |
Adds a callback called when the robot starts stabilizing before declaring connection. More... | |
bool | addUserTask (const char *name, int position, ArFunctor *functor, ArTaskState::State *state=NULL) |
Adds a user task to the list of synchronous taskes. More... | |
int | applyEncoderOffset (ArPoseWithTime from, ArTime to, ArPose *result) |
Applies the encoder motion from the passed in ArPoseWithTime to the passed in ArTime. More... | |
void | applyTransform (ArTransform trans, bool doCumulative=true) |
This applies a transform to all the robot range devices and to the sonar. More... | |
bool | areAutonomousDrivingSonarsEnabled (void) const |
returns true if the sonars are enabled for autonomous driving | |
bool | areMotorsEnabled (void) const |
returns true if the motors are enabled | |
bool | areSonarsEnabled (void) const |
returns true if the sonars are enabled More... | |
bool | areSonarsEnabledLegacy (void) const |
returns true if the sonars are enabled on legacy platforms (by checking the low level stuff) | |
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. More... | |
bool | asyncConnect (void) |
Connects to a robot, from the robots own thread. More... | |
int | asyncConnectHandler (bool tryHarderToConnect) |
This is an internal function that is used both for async connects and blocking connects use to connect. More... | |
void | attachKeyHandler (ArKeyHandler *keyHandler, bool exitOnEscape=true, bool useExitNotShutdown=true) |
Attachs a key handler. More... | |
bool | blockingConnect (void) |
Connects to a robot, not returning until connection made or failed. More... | |
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 |
Gets the closest reading in a region defined by the two points of a rectangle. More... | |
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. More... | |
double | checkRangeDevicesCurrentBox (double x1, double y1, double x2, double y2, ArPose *readingPos=NULL, const ArRangeDevice **rangeDevice=NULL, bool useLocationDependentDevices=true) const |
Gets the closest reading in a region defined by the two points of a rectangle. More... | |
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. More... | |
void | clearDirectMotion (void) |
Clears what direct motion commands have been given, so actions work. More... | |
bool | com (unsigned char command) |
Sends a command to the robot with no arguments. More... | |
bool | com2Bytes (unsigned char command, char high, char low) |
Sends a command to the robot with two bytes for argument. More... | |
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. More... | |
bool | comStr (unsigned char command, const char *argument) |
Sends a command to the robot with a length-prefixed string for argument. More... | |
bool | comStrN (unsigned char command, const char *str, int size) |
Sends a command to the robot with a length-prefixed string for argument. More... | |
void | deactivateActions (void) |
Deactivates all the actions. | |
void | disableMotors () |
Disables the motors on the robot. More... | |
void | disableSonar () |
Disables the sonar on the robot. More... | |
bool | disconnect (void) |
Disconnects from a robot. More... | |
void | dropConnection (const char *reason="Lost connection to the robot because of undefined error.") |
Internal function, shouldn't be used, drops the conn because of error. | |
void | enableAutonomousDrivingSonar () |
Enables some of the sonar on the robot (the ones for autonomous driving) More... | |
void | enableMotors () |
Enables the motors on the robot. More... | |
void | enableSonar () |
Enables the sonar on the robot. More... | |
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) More... | |
double | findAngleTo (const ArPose pose) |
Gets the angle to a point from the robot's current position and orientation. | |
const ArBatteryMTX * | findBattery (int batteryNumber) const |
Finds a battery in the robot's list (batteryNumber indices start at 1) (MTX robots only) More... | |
ArBatteryMTX * | findBattery (int batteryNumber) |
Finds a battery in the robot's list (batteryNumber indices start at 1) (MTX robots only) More... | |
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. | |
const ArLaser * | findLaser (int laserNumber) const |
Finds a laser in the robot's list (laserNumber indices start at 1) More... | |
ArLaser * | findLaser (int laserNumber) |
Finds a laser in the robot's list (laserNumber indices start at 1) More... | |
const ArLCDMTX * | findLCD (int lcdNumber=1) const |
Finds a lcd in the robot's list (lcdNumber indices start at 1) (MTX robots only) More... | |
ArLCDMTX * | findLCD (int lcdNumber=1) |
Finds a lcd in the robot's list (lcdNumber indices start at 1) (MTX robots only) More... | |
const ArRangeDevice * | findRangeDevice (const char *name, bool ignoreCase=false) const |
Finds a rangeDevice in the robot's list. More... | |
ArRangeDevice * | findRangeDevice (const char *name, bool ignoreCase=false) |
Finds a rangeDevice in the robot's list. More... | |
const ArSonarMTX * | findSonar (int sonarNumber) const |
Finds a sonar in the robot's list (sonarNumber indices start at 1) (MTX robots only) More... | |
ArSonarMTX * | findSonar (int sonarNumber) |
Finds a sonar in the robot's list (sonarNumber indices start at 1) (MTX robots only) More... | |
ArSyncTask * | findTask (const char *name) |
Finds a task by name. More... | |
ArSyncTask * | findTask (ArFunctor *functor) |
Finds a task by functor. More... | |
ArSyncTask * | findUserTask (const char *name) |
Finds a user task by name. More... | |
ArSyncTask * | findUserTask (ArFunctor *functor) |
Finds a user task by functor. More... | |
void | 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. More... | |
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 | getAbsoluteMaxTransNegVel (void) const |
Gets the robot's absolute maximum translational velocity. | |
double | getAbsoluteMaxTransVel (void) const |
Gets the robot's absolute maximum translational velocity. | |
ArResolver::ActionMap * | getActionMap (void) |
Returns the map of actions... More... | |
unsigned char | getAnalog (void) const |
Gets the analog value. | |
int | getAnalogPortSelected (void) const |
Gets which analog port is selected. | |
int | getAsyncConnectState (void) |
const std::map< int, ArBatteryMTX * > * | getBatteryMap (void) const |
Gets the battery list. More... | |
std::map< int, ArBatteryMTX * > * | getBatteryMap (void) |
Gets the battery list. More... | |
ArRobotBatteryPacketReader * | getBatteryPacketReader (void) |
Gets the battery packet reader. | |
double | getBatteryVoltage (void) const |
Gets the battery voltage of the robot (normalized to 12 volt system) More... | |
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. More... | |
ChargeState | getChargeState (void) const |
Gets the charge state of the robot (see long docs) More... | |
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. More... | |
ArTime | getConnectionOpenedTime (void) const |
Gets the time the connection to the robot was made. | |
int | getConnectionTimeoutTime (void) const |
Gets the time without a response until connection assumed lost. More... | |
double | getControl (void) const |
Gets the legacy control heading. More... | |
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. More... | |
unsigned int | getCycleWarningTime (void) const |
Gets the number of ms between cycles to warn over. More... | |
unsigned int | getCycleWarningTime (void) |
Gets the number of ms between cycles to warn over. More... | |
ArDeviceConnection * | getDeviceConnection (void) const |
Gets the connection this instance uses. More... | |
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 |
Gets the length of time a direct motion command will take precedence over actions, in milliseconds. More... | |
bool | getDoNotSwitchBaud (void) |
Gets the flag that controls if the robot won't switch baud rates. | |
const char * | getDropConnectionReason (void) |
Internal function that gets the reason the connection dropped. | |
ArRetFunctor1< double, ArPoseWithTime > * | getEncoderCorrectionCallback (void) const |
Gets the encoderCorrectionCallback. More... | |
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. More... | |
size_t | getEncoderPoseInterpNumReadings (void) const |
Sets the number of packets back in time the encoder position interpolation goes. | |
ArInterpolation * | getEncoderPoseInterpolation (void) |
int | getEncoderPoseInterpPosition (ArTime timeStamp, ArPose *position, ArPoseWithTime *mostRecent=NULL) |
Gets the encoder position the robot was at at the given timestamp. More... | |
ArRetFunctor3< int, ArTime, ArPose *, ArPoseWithTime * > * | getEncoderPoseInterpPositionCallback (void) |
Gets the callback that will call getPoseInterpPosition. | |
double | getEncoderTh (void) const |
Gets the encoder angular position ("theta") of the robot. More... | |
ArTransform | getEncoderTransform (void) const |
Gets the encoder transform. More... | |
double | getEncoderX (void) const |
Gets the encoder X position of the robot. More... | |
double | getEncoderY (void) const |
Gets the encoder Y position of the robot. More... | |
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. More... | |
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. More... | |
unsigned char | getIODigIn (int num) const |
Gets the n'th byte from the digital input data from the IO packet. More... | |
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. More... | |
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. | |
bool | getKeepControlRaw (void) |
Gets whether the control value is kept raw. | |
ArKeyHandler * | getKeyHandler (void) const |
Gets the key handler attached to this robot. | |
const std::map< int, ArLaser * > * | getLaserMap (void) const |
Gets the range device list. More... | |
std::map< int, ArLaser * > * | getLaserMap (void) |
Gets the range device list. More... | |
ArTime | getLastOdometryTime (void) const |
Gets the time the last odometry was received. More... | |
ArTime | getLastPacketTime (void) const |
Gets the time the last packet was received. More... | |
double | getLatAccel (void) const |
Gets the lateral acceleration. More... | |
double | getLatDecel (void) const |
Gets the lateral acceleration. More... | |
double | getLatVel (void) const |
Gets the current lateral velocity of the robot. More... | |
double | getLatVelMax (void) const |
Gets the maximum lateral velocity. More... | |
const std::map< int, ArLCDMTX * > * | getLCDMap (void) const |
Gets the lcd list (MTX robots only) More... | |
std::map< int, ArLCDMTX * > * | getLCDMap (void) |
Gets the lcd list (MTX robots only) More... | |
long int | getLeftEncoder (void) |
Gets packet data from the left encoder. More... | |
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 | getLogSIPContents () |
Gets if we're logging the contents of the standard SIP (motors packet) | |
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 total cumulative number of degrees the robot has turned (deg) This is a virtual odometer (by analogy with a car odometer) that measures the total linear distance the robot has travelled since ARIA connected, approximated by adding linear distance between current pose and previous pose in each ArRobot cycle. More... | |
double | getOdometerDistance (void) |
This gets the total cumulative distance the robot has travelled (mm) This is a virtual odometer (by analogy with a car odometer) that measures the total linear distance the robot has travelled since ARIA connected, approximated by adding linear distance between current pose and previous pose in each ArRobot cycle. More... | |
double | getOdometerTime (void) |
This gets the time since the robot started (sec) | |
int | getOdometryDelay (void) |
Gets the delay in odometry readings. More... | |
const ArRobotConfigPacketReader * | getOrigRobotConfig (void) const |
Gets the original robot config packet information. More... | |
ArThread::ThreadType | getOSThread (void) |
ArRobotPacketReceiver * | getPacketReceiver (void) |
Very Internal call that gets the packet sender, shouldn't be used. | |
ArRobotPacketSender * | getPacketSender (void) |
Very Internal call that gets the packet sender, shouldn't be used. | |
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. More... | |
size_t | getPoseInterpNumReadings (void) const |
Sets the number of packets back in time the position interpol goes. | |
ArInterpolation * | getPoseInterpolation (void) |
Gets the pose interpolation object, this should only really used internally. | |
int | getPoseInterpPosition (ArTime timeStamp, ArPose *position, ArPoseWithTime *mostRecent=NULL) |
Gets the position the robot was at at the given timestamp. More... | |
ArRetFunctor3< int, ArTime, ArPose *, ArPoseWithTime * > * | getPoseInterpPositionCallback (void) |
Gets the callback that will call getPoseInterpPosition. | |
ArPTZ * | getPTZ (void) |
Get PTZ interface associated with this robot. | |
std::list< ArRangeDevice * > * | getRangeDeviceList (void) |
Gets the range device list. More... | |
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. More... | |
double | getRealBatteryVoltage (void) const |
Gets the real battery voltage of the robot. More... | |
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. More... | |
ArResolver * | getResolver (void) |
Gets the resolver the robot is using. | |
long int | getRightEncoder (void) |
Gets packet data from the right encoder. More... | |
double | getRightVel (void) const |
Gets the velocity of the right wheel. | |
double | getRobotDiagonal (void) const |
Gets distance from center of robot to first vertex of octagon approximating the shape of robot. (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. More... | |
ArRobotParams * | getRobotParamsInternal (void) |
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. More... | |
double | getRotVelMax (void) const |
Gets the maximum rotational velocity. | |
std::list< ArFunctor * > * | getRunExitListCopy () |
const std::map< int, ArSonarMTX * > * | getSonarMap (void) const |
Gets the sonar list (MTX robots only) More... | |
std::map< int, ArSonarMTX * > * | getSonarMap (void) |
Gets the sonar list (MTX robots only) More... | |
int | getSonarPacCount (void) const |
Gets the number of sonar returns received in the last second. | |
int | getSonarRange (int num) const |
Gets the range of the last sonar reading for the given sonar. More... | |
ArSensorReading * | getSonarReading (int num) const |
Returns the sonar reading for the given sonar. More... | |
int | getStabilizingTime (void) const |
How long we stabilize for in ms (0 means no stabilizng) More... | |
int | getStallValue (void) const |
Gets the 2 bytes of stall and bumper flags from the robot. More... | |
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 |
Gets the number of milliseconds between state reflection refreshes if the state has not changed. More... | |
ArSyncTask * | getSyncTaskRoot (void) |
This gets the root of the syncronous task tree, only serious developers should use it. More... | |
int | getTemperature (void) const |
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. More... | |
ArTransform | getToGlobalTransform (void) const |
This gets the transform from local coords to global coords. More... | |
ArTransform | getToLocalTransform (void) const |
This gets the transform for going from global coords to local coords. More... | |
double | getTransAccel (void) const |
Gets the translational acceleration. | |
double | getTransDecel (void) const |
Gets the translational acceleration. | |
double | getTransNegVelMax (void) const |
Gets the maximum translational velocity. | |
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 time resetTripOdometer() was called (deg) This is a virtual odometer (by analogy with a car odometer) that measures the total linear distance the robot has travelled since first connected, or resetTripOdometer() was last called, approximated by adding linear distance between current pose and previous pose in each ArRobot cycle. More... | |
double | getTripOdometerDistance (void) |
This gets the distance the robot has travelled since the last time resetTripOdometer() was called (mm) This is a virtual odometer that measures the total linear distance the robot has travelled since first connected, or resetTripOdometer() was called, approximated by adding linear distance between current pose and previous pose in each ArRobot cycle. More... | |
double | getTripOdometerTime (void) |
This gets the time since the "Trip Odometer" was reset (sec) More... | |
double | getVel (void) const |
Gets the current translational velocity of the robot. | |
double | getX (void) const |
Gets the global X position of the robot. More... | |
double | getY (void) const |
Gets the global Y position of the robot. More... | |
bool | handlePacket (ArRobotPacket *packet) |
Internal function, takes a packet and passes it to the packet handlers, returns true if handled, false otherwise. | |
bool | hasBattery (ArBatteryMTX *device) const |
Finds whether a particular battery is attached to this robot or not. More... | |
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. More... | |
bool | hasLatVel (void) const |
Sees if the robot supports lateral velocities (e.g. More... | |
bool | hasLCD (ArLCDMTX *device) const |
Finds whether a particular lcd is attached to this robot or not (MTX robots only) More... | |
bool | hasRangeDevice (ArRangeDevice *device) const |
Finds whether a particular range device is attached to this robot or not. More... | |
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 | hasSonar (ArSonarMTX *device) const |
Finds whether a particular sonar is attached to this robot or not (MTX robots only) More... | |
bool | hasStateOfCHarge () const |
Gets if the state of charge value is in use. More... | |
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 | haveRequestedEncoderPackets (void) |
Sees if we've explicitly requested encoder packets. | |
bool | haveRequestedIOPackets (void) |
Sees if we've explicitly requested IO packets. | |
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. More... | |
void | internalIgnoreNextPacket (void) |
void | internalSetFakeFirstEncoderPose (bool fakeFirstEncoderPose) |
bool | isChargerPowerGood (void) const |
Gets if the robot is on a charger. | |
bool | isConnected (void) const |
Questions whether the robot is connected or not. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
bool | isSonarNew (int num) const |
Find out if the given sonar reading was newly refreshed by the last incoming SIP received. More... | |
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. More... | |
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) More... | |
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. More... | |
void | logUserTasks (void) const |
Logs the list of user tasks, strictly for your viewing pleasure. More... | |
void | loopOnce (void) |
This function loops once... only serious developers should use it. More... | |
bool | madeConnection (bool resetConnectionTime=true) |
Internal function, shouldn't be used, does the initial conn stuff. | |
void | move (double distance) |
Move the given distance forward/backwards. More... | |
void | moveTo (ArPose pose, bool doCumulative=true) |
Change stored pose (i.e. the value returned by getPose()) More... | |
void | moveTo (ArPose to, ArPose from, bool doCumulative=true) |
Change stored pose (i.e. the value returned by getPose()) More... | |
void | packetHandler (void) |
Packet Handler, internal (calls old or new as appropriate) | |
void | packetHandlerNonThreaded (void) |
Packet handler, internal, for use in the syncloop when there's no threading. More... | |
void | packetHandlerThreadedProcessor (void) |
Packet handler, internal, for use in the syncloop to handle the actual packets. | |
void | packetHandlerThreadedReader (void) |
Packet handler, internal, for using from a thread to actually read all the packets. More... | |
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. More... | |
void | processNewSonar (char number, int range, ArTime timeReceived) |
Processes a new sonar reading, internal. More... | |
void | processParamFile (void) |
bool | remAction (ArAction *action) |
Removes an action from the list, by pointer. More... | |
bool | remAction (const char *actionName) |
Removes an action from the list, by name. More... | |
bool | remBattery (ArBatteryMTX *battery) |
Remove a battery from the robot's list, by instance (MTX robots only) Primarily for ARIA internal use only. More... | |
bool | remBattery (int batteryNumber) |
Remove a battery from the robot's list, by number (MTX robots only) Primarily for ARIA internal use only. More... | |
void | remConnectCB (ArFunctor *functor) |
Removes a connect callback. More... | |
void | remDisconnectNormallyCB (ArFunctor *functor) |
Removes a callback for when disconnect is called while connected. More... | |
void | remDisconnectOnErrorCB (ArFunctor *functor) |
Removes a callback for when disconnection happens because of an error. More... | |
void | remFailedConnectCB (ArFunctor *functor) |
Removes a callback for when a connection to the robot is failed. More... | |
bool | remLaser (ArLaser *laser, bool removeAsRangeDevice=true) |
Remove a range device from the robot's list, by instance. More... | |
bool | remLaser (int laserNumber, bool removeAsRangeDevice=true) |
Remove a range device from the robot's list, by number. More... | |
bool | remLCD (ArLCDMTX *lcd) |
Remove a lcd from the robot's list, by instance. More... | |
bool | remLCD (int lcdNumber) |
Remove a lcd from the robot's list, by number. More... | |
void | remPacketHandler (ArRetFunctor1< bool, ArRobotPacket *> *functor) |
Removes a packet handler from the list of packet handlers. More... | |
void | remRangeDevice (const char *name) |
Remove a range device from the robot's list, by name. More... | |
void | remRangeDevice (ArRangeDevice *device) |
Remove a range device from the robot's list, by instance. More... | |
void | remRunExitCB (ArFunctor *functor) |
Removes a callback for when the run loop exits for what ever reason. More... | |
void | remSensorInterpTask (const char *name) |
Removes a sensor interp tasks by name. More... | |
void | remSensorInterpTask (ArFunctor *functor) |
Removes a sensor interp tasks by functor. More... | |
void | remSetEncoderTransformCB (ArFunctor *functor) |
Removes a callback for when the encoder transform is changed. | |
bool | remSonar (ArSonarMTX *sonar) |
Remove a sonar from the robot's list, by instance. More... | |
bool | remSonar (int sonarNumber) |
Remove a sonar from the robot's list, by number. More... | |
void | remStabilizingCB (ArFunctor *functor) |
Removes stabilizing callback. More... | |
void | remUserTask (const char *name) |
Removes a user task from the list of synchronous taskes by name. More... | |
void | remUserTask (ArFunctor *functor) |
Removes a user task from the list of synchronous taskes by functor. More... | |
void | requestEncoderPackets (void) |
Starts a continuous stream of encoder packets. More... | |
void | requestIOPackets (void) |
Starts a continuous stream of IO packets. More... | |
void | resetTripOdometer (void) |
Resets the "Trip Odometer". More... | |
void | robotLocker (void) |
Robot locker, internal. | |
void | robotUnlocker (void) |
Robot unlocker, internal. | |
void | run (bool stopRunIfNotConnected, bool runNonThreaded=false) |
Starts the instance to do processing in this thread. More... | |
void | runAsync (bool stopRunIfNotConnected, bool runNonThreadedPacketReader=false) |
Starts the instance to do processing in its own new thread. More... | |
bool | setAbsoluteMaxLatAccel (double maxAccel) |
Sets the robot's absolute maximum lateral acceleration. More... | |
bool | setAbsoluteMaxLatDecel (double maxDecel) |
Sets the robot's absolute maximum lateral deceleration. More... | |
bool | setAbsoluteMaxLatVel (double maxVel) |
Sets the robot's absolute maximum lateral velocity. More... | |
bool | setAbsoluteMaxRotAccel (double maxAccel) |
Sets the robot's absolute maximum rotational acceleration. More... | |
bool | setAbsoluteMaxRotDecel (double maxDecel) |
Sets the robot's absolute maximum rotational deceleration. More... | |
bool | setAbsoluteMaxRotVel (double maxVel) |
Sets the robot's absolute maximum rotational velocity. More... | |
bool | setAbsoluteMaxTransAccel (double maxAccel) |
Sets the robot's absolute maximum translational acceleration. More... | |
bool | setAbsoluteMaxTransDecel (double maxDecel) |
Sets the robot's absolute maximum translational deceleration. More... | |
bool | setAbsoluteMaxTransNegVel (double maxVel) |
Sets the robot's absolute maximum translational velocity. More... | |
bool | setAbsoluteMaxTransVel (double maxVel) |
Sets the robot's absolute maximum translational velocity. More... | |
void | setBatteryInfo (double realBatteryVoltage, double normalizedBatteryVoltage, bool haveStateOfCharge, double stateOfCharge) |
Sets the battery info. | |
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. More... | |
void | setConnectionTimeoutTime (int mSecs) |
Sets the time without a response until connection assumed lost. More... | |
void | setConnectWithNoParams (bool connectWithNoParams) |
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. More... | |
void | setCycleWarningTime (unsigned int ms) |
Sets the number of ms between cycles to warn over. More... | |
void | setDeadReconPose (ArPose pose) |
Sets the dead recon position of the robot. More... | |
void | setDeltaHeading (double deltaHeading) |
Sets the delta heading. More... | |
void | setDeviceConnection (ArDeviceConnection *connection) |
Sets the connection this instance uses. More... | |
void | setDirectMotionPrecedenceTime (int mSec) |
Sets the length of time a direct motion command will take precedence over actions, in milliseconds. More... | |
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. More... | |
void | setEncoderPose (ArPose encoderPose) |
Sets the encoder pose, for internal use. | |
void | setEncoderPoseInterpNumReadings (size_t numReadings) |
Sets the number of packets back in time the ArInterpolation goes for encoder readings. | |
void | setEncoderTransform (ArPose deadReconPos, ArPose globalPos) |
Changes the transform. More... | |
void | setEncoderTransform (ArPose transformPos) |
Changes the transform directly. More... | |
void | setEncoderTransform (ArTransform transform) |
Changes the transform directly. | |
void | setHeading (double heading) |
Sets the heading. More... | |
void | setHeadingDoneDiff (double degrees) |
sets the difference required for being done with a heading change (e.g. used in isHeadingDone()) | |
void | setIgnoreMicroControllerBatteryInfo (bool ignoreMicroControllerBatteryInfo) |
Sets things so that the battery info from the microcontroller will be ignored. | |
void | setIsChargerPowerGood (bool onCharger) |
Sets if we're on the charger (for use with setting the state of charge) | |
void | setKeepControlRaw (bool keepControlRaw) |
Sets whether to keep the control value raw or not. | |
void | setLatAccel (double acc) |
Sets the lateral acceleration. More... | |
void | setLatDecel (double decel) |
Sets the lateral acceleration. More... | |
void | setLatVel (double latVelocity) |
Sets the lateral velocity. More... | |
void | setLatVelMax (double vel) |
Sets the maximum lateral velocity. More... | |
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 | setLogSIPContents (bool logSIP) |
Set if we're logging the contents of the standard SIP (motor packets) | |
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 | setMTXTimeUSecCB (ArRetFunctor1< bool, ArTypes::UByte4 *> *functor) |
Adds a callback that'll be used to see the time on the computer side (for an MTX) | |
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. More... | |
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) |
Associates an ArPTZ object with this robot (see getPTZ()) | |
void | setRawEncoderPose (ArPose rawEncoderPose) |
Sets the raw encoder pose, for internal use. | |
void | setRealBatteryVoltageAverageOfNum (size_t numToAverage) |
Sets the number of readings the real battery voltage is the average of (default 20) | |
void | setRequireConfigPacket (bool requireConfigPacket) |
Sets if a config packet is requried or not... More... | |
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) More... | |
void | setRotAccel (double acc) |
Sets the rotational acceleration. | |
void | setRotDecel (double decel) |
Sets the rotational acceleration. | |
void | setRotVel (double velocity) |
Sets the rotational velocity. More... | |
void | setRotVelMax (double vel) |
Sets the maximum rotational velocity. | |
void | setStabilizingTime (int mSecs) |
How long we should stabilize for in ms (0 disables stabilizing) More... | |
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) |
Sets the number of milliseconds between state reflection refreshes if the state has not changed. More... | |
void | setTransAccel (double acc) |
Sets the translational acceleration. | |
void | setTransDecel (double decel) |
Sets the translational acceleration. | |
void | setTransNegVelMax (double negVel) |
Sets the maximum translational velocity. | |
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) |
Sets the velocity. More... | |
void | setVel2 (double leftVelocity, double rightVelocity) |
Sets the velocity of the wheels independently. More... | |
void | startStabilization (void) |
Internal function, shouldn't be used, calls the preconnected stuff. | |
void | stateReflector (void) |
State Reflector, internal. More... | |
void | stop (void) |
Stops the robot. More... | |
void | stopEncoderPackets (void) |
Stops a continuous stream of encoder packets. More... | |
void | stopIOPackets (void) |
Stops a continuous stream of IO packets. | |
void | stopRunning (bool doDisconnect=true) |
Stops the robot from doing any more processing. More... | |
void | stopStateReflection (void) |
Sets the state reflection to be inactive (until motion or clearDirectMotion) More... | |
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. More... | |
WaitState | waitForConnectOrConnFail (unsigned int msecs=0) |
Suspend calling thread until the ArRobot is connected or fails to connect. More... | |
WaitState | waitForRunExit (unsigned int msecs=0) |
Suspend calling thread until the ArRobot run loop has exited. More... | |
void | wakeAllConnOrFailWaitingThreads () |
Wake up all threads waiting for connection or connection failure. More... | |
void | wakeAllConnWaitingThreads () |
Wake up all threads waiting for connection. More... | |
void | wakeAllRunExitWaitingThreads () |
Wake up all threads waiting for the run loop to exit. More... | |
void | wakeAllWaitingThreads () |
Wake up all threads waiting on this robot. More... | |
~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 Member Functions | |
void | reset (void) |
Protected Attributes | |
double | myAbsoluteMaxLatAccel |
double | myAbsoluteMaxLatDecel |
double | myAbsoluteMaxLatVel |
double | myAbsoluteMaxRotAccel |
double | myAbsoluteMaxRotDecel |
double | myAbsoluteMaxRotVel |
double | myAbsoluteMaxTransAccel |
double | myAbsoluteMaxTransDecel |
double | myAbsoluteMaxTransNegVel |
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 |
bool | myAutonomousDrivingSonarEnabled |
ArRunningAverage | myBatteryAverager |
std::map< int, ArBatteryMTX * > | myBatteryMap |
ArRobotBatteryPacketReader * | myBatteryPacketReader |
double | myBatteryVoltage |
bool | myBlockingConnectRun |
ChargeState | myChargeState |
double | myCompass |
ArDeviceConnection * | myConn |
std::list< ArFunctor * > | myConnectCBList |
ArCondition | myConnectCond |
unsigned int | myConnectionCycleMultiplier |
ArTime | myConnectionOpenedTime |
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 |
std::string | myDropConnectionReason |
ArRetFunctor1< double, ArPoseWithTime > * | myEncoderCorrectionCB |
ArTransform | myEncoderGlobalTrans |
ArInterpolation | myEncoderInterpolation |
ArPoseWithTime | myEncoderPose |
ArRetFunctor3C< int, ArRobot, ArTime, ArPose *, ArPoseWithTime * > | myEncoderPoseInterpPositionCB |
ArTime | myEncoderPoseTaken |
ArTransform | myEncoderTransform |
std::list< ArFunctor * > | myFailedConnectCBList |
bool | myFakeFirstEncoderPose |
int | myFaultFlags |
bool | myFirstEncoderPose |
int | myFlags |
ArPose | myGlobalPose |
bool | myHasFaultFlags |
bool | myHaveStateOfCharge |
double | myHeadingDoneDiff |
bool | myIgnoreMicroControllerBatteryInfo |
bool | myIgnoreNextPacket |
ArInterpolation | myInterpolation |
int | myIOAnalog [128] |
int | myIOAnalogSize |
unsigned char | myIODigIn [255] |
int | myIODigInSize |
unsigned char | myIODigOut [255] |
int | myIODigOutSize |
bool | myIsChargerPowerGood |
bool | myIsConnected |
bool | myIsStabilizing |
bool | myKeepControlRaw |
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 | myLastSentRotVelNegMax |
double | myLastSentRotVelPosMax |
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 |
std::map< int, ArLCDMTX * > | myLCDMap |
long int | myLeftEncoder |
double | myLeftVel |
bool | myLogActions |
bool | myLogMovementReceived |
bool | myLogMovementSent |
bool | myLogSIPContents |
bool | myLogVelocitiesReceived |
int | myMotorPacCount |
int | myMotorPacCurrentCount |
double | myMoveDoneDist |
ArRetFunctor1< bool, ArTypes::UByte4 * > * | myMTXTimeUSecCB |
ArMutex | myMutex |
std::string | myName |
bool | myNoTimeWarningThisCycle |
int | myNumSonar |
double | myOdometerDegrees |
double | myOdometerDistance |
ArTime | myOdometerStart |
int | myOdometryDelay |
ArRobotConfigPacketReader * | myOrigRobotConfig |
bool | myOverriddenChargeState |
bool | myOverriddenIsChargerPowerGood |
bool | myOwnTheResolver |
std::list< ArRetFunctor1< bool, ArRobotPacket * > * > | myPacketHandlerList |
std::list< ArRobotPacket * > | myPacketList |
ArMutex | myPacketMutex |
ArRobotPacketReaderThread | myPacketReader |
ArCondition | myPacketReceivedCondition |
bool | myPacketsReceivedTracking |
long | myPacketsReceivedTrackingCount |
ArTime | myPacketsReceivedTrackingStarted |
bool | myPacketsSentTracking |
ArRobotParams * | myParams |
ArRetFunctor3C< int, ArRobot, ArTime, ArPose *, ArPoseWithTime * > | myPoseInterpPositionCB |
ArPTZ * | myPtz |
std::list< ArRangeDevice * > | myRangeDeviceList |
ArPoseWithTime | myRawEncoderPose |
ArRunningAverage | myRealBatteryAverager |
double | myRealBatteryVoltage |
ArRobotPacketReceiver | myReceiver |
bool | myRequestedEncoderPackets |
bool | myRequestedIOPackets |
bool | myRequireConfigPacket |
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 |
bool | myRunningNonThreaded |
ArRobotPacketSender | mySender |
bool | mySentPulse |
ArCallbackList | mySetEncoderTransformCBList |
bool | mySonarEnabled |
std::map< int, ArSonarMTX * > | mySonarMap |
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 |
double | myTransNegVelMax |
ArTime | myTransSetTime |
TransDesired | myTransType |
double | myTransVal |
double | myTransVal2 |
double | myTransVelMax |
double | myTripOdometerDegrees |
double | myTripOdometerDistance |
ArTime | myTripOdometerStart |
bool | myTryingToMove |
double | myVel |
bool | myWarnedAboutExtraSonar |
Central class for communicating with and operating the robot.
This is the most important class. It is used to communicate with the robot by sending commands and retrieving data (including wheel odometry, digital and analog inputs, sonar data, and more). It is also used to provide access to objects for controlling attached accessories, ArRangeDevice objects, ArAction objects, and others. For details on usage, and how the task cycle and obot state synchronization works, see the ArRobot section and the Commands and Actions section of the ARIA overview.
enum ArRobot::WaitState |
ArRobot::ArRobot | ( | const char * | name = NULL , |
bool | obsolete = true , |
||
bool | doSigHandle = true , |
||
bool | normalInit = true , |
||
bool | addAriaExitCallback = true |
||
) |
Constructor.
The parameters only rarely need to be specified.
name | A name for this robot, useful if a program has more than one ArRobot object |
obsolete | This parameter is ignored. (It used to turn off state reflection if false, but that is no longer possible.) |
doSigHandle | do normal signal handling and have this robot instance stopRunning() when the program is signaled |
normalInit | whether the robot should initializes its structures or the calling program will take care of it. No one will probalby ever use this value, since if they are doing that then overriding will probably be more useful, but there it is. |
addAriaExitCallback | If true (default), add callback to global Aria class to stop running the processing loop and disconnect from robot when Aria::exit() is called. If false, do not disconnect on Aria::exit() |
MPL 20130509 making this default to true, so that things that use loopOnce and not one of the run calls can work (the run calls set this to whatever it should be anyway)
void ArRobot::actionHandler | ( | void | ) |
bool ArRobot::addAction | ( | ArAction * | action, |
int | priority | ||
) |
Adds an action to the list with the given priority.
Adds an action to the list of actions with the given priority.
In the case of two (or more) actions with the same priority, the default resolver (ArPriorityResolver) averages the the multiple readings. The priority can be any integer, but as a convention 0 to 100 is used, with 100 being the highest priority. The default resolver (ArPriorityResolver) resolves the actions in order of descending priority. For example, an action with priority 100 is evaluated before one with priority 99, followed by 50, etc. This means that an action with a higher priority may be able to supercede a lower-priority action's desired value for a certain output to a lesser or greater degree, depending on how high a "strength" value it sets. See the overview of ARIA in this reference manual for more discussion on Actions.
action | the action to add |
priority | what importance to give the action; how to order the actions. High priority actions are evaluated by the action resolvel before lower priority actions. |
bool ArRobot::addBattery | ( | ArBatteryMTX * | battery, |
int | batteryNumber | ||
) |
Adds a battery to the robot's map of them.
void ArRobot::addConnectCB | ( | ArFunctor * | functor, |
ArListPos::Pos | position = ArListPos::LAST |
||
) |
Adds a connect callback.
Adds a connect callback, which is an ArFunctor, (created as an ArFunctorC).
The entire list of connect callbacks is called when a connection is made with the robot. If you have some sort of module that adds a callback, that module must remove the callback when the module is removed.
functor | A functor (created from ArFunctorC) which refers to the function to call. |
position | whether to place the functor first or last |
void ArRobot::addDisconnectNormallyCB | ( | ArFunctor * | functor, |
ArListPos::Pos | position = ArListPos::LAST |
||
) |
Adds a callback for when disconnect is called while connected.
Adds a disconnect normally callback,which is an ArFunctor, created as an ArFunctorC.
This whole list of disconnect normally callbacks is called when something calls disconnect if the instance isConnected. If there is no connection and disconnect is called nothing is done. If you have some sort of module that adds a callback, that module must remove the callback when the module is removed.
functor | functor created from ArFunctorC which refers to the function to call. |
position | whether to place the functor first or last |
void ArRobot::addDisconnectOnErrorCB | ( | ArFunctor * | functor, |
ArListPos::Pos | position = ArListPos::LAST |
||
) |
Adds a callback for when disconnection happens because of an error.
Adds a disconnect on error callback, which is an ArFunctor, created as an ArFunctorC.
This whole list of disconnect on error callbacks is called when ARIA loses connection to a robot because of an error. This can occur if the physical connection (ie serial cable) between the robot and the computer is severed/disconnected, if one of a pair of radio modems that connect the robot and computer are disconnected, if someone presses the reset button on the robot, or if the simulator is closed while ARIA is connected to it. Note that if the link between the two is lost the ARIA assumes it is temporary until it reaches a timeout value set with setConnectionTimeoutTime. If you have some sort of module that adds a callback, that module must remove the callback when the module removed.
functor | functor created from ArFunctorC which refers to the function to call. |
position | whether to place the functor first or last |
void ArRobot::addFailedConnectCB | ( | ArFunctor * | functor, |
ArListPos::Pos | position = ArListPos::LAST |
||
) |
Adds a callback for when a connection to the robot is failed.
Adds a failed connect callback,which is an ArFunctor, created as an ArFunctorC.
This whole list of failed connect callbacks is called when an attempt is made to connect to the robot, but fails. The usual reason for this failure is either that there is no robot/sim where the connection was tried to be made, the robot wasn't given a connection, or the radio modems that communicate with the robot aren't on. If you have some sort of module that adds a callback, that module must remove the callback when the module removed.
functor | functor created from ArFunctorC which refers to the function to call. |
position | whether to place the functor first or last |
bool ArRobot::addLaser | ( | ArLaser * | laser, |
int | laserNumber, | ||
bool | addAsRangeDevice = true |
||
) |
Adds a laser to the robot's map of them.
bool ArRobot::addLCD | ( | ArLCDMTX * | lcd, |
int | lcdNumber | ||
) |
Adds a lcd to the robot's map of them.
void ArRobot::addPacketHandler | ( | ArRetFunctor1< bool, ArRobotPacket *> * | functor, |
ArListPos::Pos | position = ArListPos::LAST |
||
) |
Adds a packet handler to the list of packet handlers.
Adds a packet handler.
A packet handler is an ArRetFunctor1<bool, ArRobotPacket*>, (e.g. created as an instance of ArRetFunctor1C. The return is a boolean, while the functor takes an ArRobotPacket pointer as the argument. This functor is placed in a list of functors to call when a packet arrives. This list is processed in order until one of the handlers returns true. Your packet handler function may be invoked for any packet, so it should test the packet type ID (see ArRobotPacket::getID()). If you handler gets data from the packet (it "handles" it) it should return true, to prevent ArRobot from invoking other handlers with the packet (with data removed). If you hander cannot interpret the packet, it should leave it unmodified and return false to allow other handlers a chance to receive it.
functor | the functor to call when the packet comes in |
position | whether to place the functor first or last |
void ArRobot::addRangeDevice | ( | ArRangeDevice * | device | ) |
Adds a rangeDevice to the robot's list of them, and set the ArRangeDevice object's robot pointer to this ArRobot object.
void ArRobot::addRunExitCB | ( | ArFunctor * | functor, |
ArListPos::Pos | position = ArListPos::LAST |
||
) |
Adds a callback for when the run loop exits for what ever reason.
Adds a callback that is called when the run loop exits.
The functor is which is an ArFunctor, created as an ArFunctorC. The whole list of functors is called when the run loop exits. This is most usefull for threaded programs that run the robot using ArRobot::runAsync. This will allow user threads to know when the robot loop has exited.
functor | functor created from ArFunctorC which refers to the function to call. |
position | whether to place the functor first or last |
bool ArRobot::addSensorInterpTask | ( | const char * | name, |
int | position, | ||
ArFunctor * | functor, | ||
ArTaskState::State * | state = NULL |
||
) |
Adds a task under the sensor interp part of the syncronous tasks.
The synchronous tasks get called every robot cycle (every 100 ms by default).
name | the name to give to the task, should be unique |
position | the place in the list of user tasks to place this task, this can be any integer, though by convention 0 to 100 is used. The tasks are called in order of highest number to lowest number. |
functor | functor created from ArFunctorC which refers to the function to call. |
state | Optional pointer to external ArSyncTask state variable; normally not needed and may be NULL or omitted. |
bool ArRobot::addSonar | ( | ArSonarMTX * | sonar, |
int | sonarNumber | ||
) |
Adds a sonar to the robot's map of them.
void ArRobot::addStabilizingCB | ( | ArFunctor * | functor, |
ArListPos::Pos | position = ArListPos::LAST |
||
) |
Adds a callback called when the robot starts stabilizing before declaring connection.
Adds a stablizing callback, which is an ArFunctor, created as an ArFunctorC.
The entire list of connect callbacks is called just before the connection is called done to the robot. This time can be used to calibtrate readings (on things like gyros).
functor | The functor to call (e.g. ArFunctorC) |
position | whether to place the functor first or last |
bool ArRobot::addUserTask | ( | const char * | name, |
int | position, | ||
ArFunctor * | functor, | ||
ArTaskState::State * | state = NULL |
||
) |
Adds a user task to the list of synchronous taskes.
The synchronous tasks get called every robot cycle (every 100 ms by default).
name | the name to give to the task, should be unique |
position | the place in the list of user tasks to place this task, this can be any integer, though by convention 0 to 100 is used. The tasks are called in order of highest number to lowest position number. |
functor | functor created from ArFunctorC which refers to the function to call. |
state | Optional pointer to external ArSyncTask state variable; normally not needed and may be NULL or omitted. |
int ArRobot::applyEncoderOffset | ( | ArPoseWithTime | from, |
ArTime | to, | ||
ArPose * | result | ||
) |
Applies the encoder motion from the passed in ArPoseWithTime to the passed in ArTime.
from | the pose with time to apply the offset from... it applies the encoder mostion from the time on this to the to param |
to | the time to find the offset to |
result | the pose to put the result in |
void ArRobot::applyTransform | ( | ArTransform | trans, |
bool | doCumulative = true |
||
) |
This applies a transform to all the robot range devices and to the sonar.
Applies a transform to the range devices and sonar...
this is mostly useful for translating to/from local/global coords, but may have other uses
trans | the transform to apply |
doCumulative | whether to transform the cumulative buffers or not |
|
inline |
returns true if the sonars are enabled
This used to just check the low level firmware values, but that's now done by areSonarsEnabledLegacy.
bool ArRobot::asyncConnect | ( | void | ) |
Connects to a robot, from the robots own thread.
Sets up the robot to connect, then returns, but the robot must be running (ie from runAsync) before you do this.
Most programs should use ArRobotConnector to perform the connection rather than using thin method directly.
This function 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).
int ArRobot::asyncConnectHandler | ( | bool | tryHarderToConnect | ) |
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.
tryHarderToConnect | if this is true, then if the radio modems look like they aren't working, it'll take about 2 seconds to try and connect them, whereas if its false, it'll do a little try, but won't try very hard |
void ArRobot::attachKeyHandler | ( | ArKeyHandler * | keyHandler, |
bool | exitOnEscape = true , |
||
bool | useExitNotShutdown = true |
||
) |
Attachs a key handler.
This will attach a key handler to a robot, by putting it into the robots sensor interp task list (a keyboards a sensor of users will, right?).
By default exitOnEscape is true, which will cause this function to add an escape key handler to the key handler, this will make the program exit when escape is pressed... if you don't like this you can pass exitOnEscape in as false.
keyHandler | the key handler to attach |
exitOnEscape | whether to exit when escape is pressed or not |
useExitNotShutdown | if true then Aria::exit will be called instead of Aria::shutdown if it tries to exit |
bool ArRobot::blockingConnect | ( | void | ) |
Connects to a robot, not returning until connection made or failed.
Connects to the robot, returning only when a connection has been made or it has been established a connection can't be made.
Most programs should use an ArRobotConnector object to perform the connection rather than using this method directly.
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).
double ArRobot::checkRangeDevicesCumulativeBox | ( | double | x1, |
double | y1, | ||
double | x2, | ||
double | y2, | ||
ArPose * | readingPos = NULL , |
||
const ArRangeDevice ** | rangeDevice = NULL , |
||
bool | useLocationDependentDevices = true |
||
) | const |
Gets the closest reading in a region defined by the two points of a rectangle.
This goes through all of the registered range devices and locks each, calls cumulativeReadingBox() on it, and then unlocks it. If a reading was found in the box, returns with results.
x1 | the x coordinate of one of the rectangle points |
y1 | the y coordinate of one of the rectangle points |
x2 | the x coordinate of the other rectangle point |
y2 | the y coordinate of the other rectangle point |
readingPos | If not NULL, a pointer to a position in which to store the location of the closest position |
rangeDevice | If not NULL, a pointer in which to store a pointer to the range device that provided the closest reading in the box. |
useLocationDependentDevices | If false, ignore sensor devices that are "location dependent". If true, include them in this check. |
double ArRobot::checkRangeDevicesCumulativePolar | ( | double | startAngle, |
double | endAngle, | ||
double * | angle = NULL , |
||
const ArRangeDevice ** | rangeDevice = NULL , |
||
bool | useLocationDependentDevices = true |
||
) | const |
Goes through all the range devices and checks them.
Find the closest reading from any range device's set of cumulative readings within a polar region or "slice" defined by the given angle range.
This function iterates through each registered range device (see addRangeDevice()), calls ArRangeDevice::lockDevice(), uses ArRangeDevice::cumulativeReadingPolar() to find a reading, then calls ArRangeDevice::unlockDevice().
Gets the closest cumulative reading in the given polar region. 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.
startAngle | where to start the slice |
endAngle | where to end the slice, going counterclockwise from startAngle |
angle | if given, a pointer to a value in which to put the specific angle to the found reading |
Example:
rangeDevice | If not null, then a pointer to the ArRangeDevice that provided the returned reading is placed in this variable. |
useLocationDependentDevices | If false, ignore sensor devices that are "location dependent". If true, include them in this check. |
double ArRobot::checkRangeDevicesCurrentBox | ( | double | x1, |
double | y1, | ||
double | x2, | ||
double | y2, | ||
ArPose * | readingPos = NULL , |
||
const ArRangeDevice ** | rangeDevice = NULL , |
||
bool | useLocationDependentDevices = true |
||
) | const |
Gets the closest reading in a region defined by the two points of a rectangle.
This goes through all of the registered range devices and locks each, calls currentReadingBox on it, and then unlocks it.
x1 | the x coordinate of one of the rectangle points |
y1 | the y coordinate of one of the rectangle points |
x2 | the x coordinate of the other rectangle point |
y2 | the y coordinate of the other rectangle point |
readingPos | a pointer to a position in which to store the location of |
rangeDevice | If not null, then a pointer to the ArRangeDevice that provided the returned reading is placed in this variable. the closest position |
useLocationDependentDevices | If false, ignore sensor devices that are "location dependent". If true, include them in this check. |
double ArRobot::checkRangeDevicesCurrentPolar | ( | double | startAngle, |
double | endAngle, | ||
double * | angle = NULL , |
||
const ArRangeDevice ** | rangeDevice = NULL , |
||
bool | useLocationDependentDevices = true |
||
) | const |
Goes through all the range devices and checks them.
Find the closest reading from any range device's set of current readings within a polar region or "slice" defined by the given angle range.
This function iterates through each registered range device (see addRangeDevice()), calls ArRangeDevice::lockDevice(), uses ArRangeDevice::currentReadingPolar() to find a reading, then calls ArRangeDevice::unlockDevice().
Gets the closest current reading in the given polar region. 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.
startAngle | where to start the slice |
endAngle | where to end the slice, going counterclockwise from startAngle |
angle | if given, a pointer to a value in which to put the specific angle to the found reading |
Example:
rangeDevice | If not null, then a pointer to the ArRangeDevice that provided the returned reading is placed in this variable. |
useLocationDependentDevices | If false, ignore sensor devices that are "location dependent". If true, include them in this check. |
void ArRobot::clearDirectMotion | ( | void | ) |
Clears what direct motion commands have been given, so actions work.
This clears the direct motion commands so that actions will be allowed to control the robot again.
bool ArRobot::com | ( | unsigned char | command | ) |
Sends a command to the robot with no arguments.
command | the command number to send |
bool ArRobot::com2Bytes | ( | unsigned char | command, |
char | high, | ||
char | low | ||
) |
Sends a command to the robot with two bytes for argument.
command | the command number to send |
high | the high byte to send with the command |
low | the low byte to send with the command |
bool ArRobot::comInt | ( | unsigned char | command, |
short int | argument | ||
) |
Sends a command to the robot with an int for argument.
command | the command number to send |
argument | the integer argument to send with the command |
bool ArRobot::comStr | ( | unsigned char | command, |
const char * | argument | ||
) |
Sends a command to the robot with a length-prefixed string for argument.
command | the command number to send |
argument | NULL-terminated string to get data from to send with the command; length to send with packet is determined by strlen |
bool ArRobot::comStrN | ( | unsigned char | command, |
const char * | str, | ||
int | size | ||
) |
Sends a command to the robot with a length-prefixed string for argument.
Sends a length-prefixed string command to the robot, copying 'size' bytes of data from 'str' into the packet.
command | the command number to send |
str | copy data to send from this character array |
size | length of the string to send; copy this many bytes from 'str'; use this value as the length prefix byte before the sent string. This length must be less than the maximum packet size of 200. |
void ArRobot::disableMotors | ( | ) |
Disables the motors on the robot.
This command disables the motors on the robot, if it is connected.
void ArRobot::disableSonar | ( | ) |
Disables the sonar on the robot.
This command disables the sonars on the robot, if it is connected.
bool ArRobot::disconnect | ( | void | ) |
Disconnects from a robot.
This also calls of the DisconnectNormally Callback Functors if the robot was actually connected to a robot when this member was called. Then it disables the robot motors, sends CLOSE command to robot, waits one seconds, and closes the communications connection. This disconnection normally happens automatically when the program exits by calling Aria::exit(), or if communication to the robot fails during the run cycle, and this method does not need to be explicitly called.
void ArRobot::enableAutonomousDrivingSonar | ( | ) |
Enables some of the sonar on the robot (the ones for autonomous driving)
This command enables the sonars on the robot, if it is connected.
void ArRobot::enableMotors | ( | ) |
Enables the motors on the robot.
This command enables the motors on the robot, if it is connected.
void ArRobot::enableSonar | ( | ) |
Enables the sonar on the robot.
This command enables the sonars on the robot, if it is connected.
ArAction * ArRobot::findAction | ( | const char * | actionName | ) |
Returns the first (highest priority) action with the given name (or NULL)
Finds the action with the given name...
if more than one action has that name it find the one with the highest priority
actionName | the name of the action we want to find |
const ArBatteryMTX * ArRobot::findBattery | ( | int | batteryNumber | ) | const |
Finds a battery in the robot's list (batteryNumber indices start at 1) (MTX robots only)
ArBatteryMTX * ArRobot::findBattery | ( | int | batteryNumber | ) |
Finds a battery in the robot's list (batteryNumber indices start at 1) (MTX robots only)
const ArLaser * ArRobot::findLaser | ( | int | laserNumber | ) | const |
Finds a laser in the robot's list (laserNumber indices start at 1)
ArLaser * ArRobot::findLaser | ( | int | laserNumber | ) |
Finds a laser in the robot's list (laserNumber indices start at 1)
const ArLCDMTX * ArRobot::findLCD | ( | int | lcdNumber = 1 | ) | const |
Finds a lcd in the robot's list (lcdNumber indices start at 1) (MTX robots only)
ArLCDMTX * ArRobot::findLCD | ( | int | lcdNumber = 1 | ) |
Finds a lcd in the robot's list (lcdNumber indices start at 1) (MTX robots only)
const ArRangeDevice * ArRobot::findRangeDevice | ( | const char * | name, |
bool | ignoreCase = false |
||
) | const |
Finds a rangeDevice in the robot's list.
name | return the first device with this name |
ignoreCase | true to ignore case, false to pay attention to it |
ArRangeDevice * ArRobot::findRangeDevice | ( | const char * | name, |
bool | ignoreCase = false |
||
) |
Finds a rangeDevice in the robot's list.
name | return the first device with this name |
ignoreCase | true to ignore case, false to pay attention to it |
const ArSonarMTX * ArRobot::findSonar | ( | int | sonarNumber | ) | const |
Finds a sonar in the robot's list (sonarNumber indices start at 1) (MTX robots only)
ArSonarMTX * ArRobot::findSonar | ( | int | sonarNumber | ) |
Finds a sonar in the robot's list (sonarNumber indices start at 1) (MTX robots only)
ArSyncTask * ArRobot::findTask | ( | const char * | name | ) |
Finds a task by name.
Finds a task by its name, searching the entire space of tasks.
ArSyncTask * ArRobot::findTask | ( | ArFunctor * | functor | ) |
Finds a task by functor.
Finds a task by its functor, searching the entire space of tasks.
ArSyncTask * ArRobot::findUserTask | ( | const char * | name | ) |
Finds a user task by name.
Finds a user task by its name, searching the entire space of tasks.
ArSyncTask * ArRobot::findUserTask | ( | ArFunctor * | functor | ) |
Finds a user task by functor.
Finds a user task by its functor, searching the entire space of tasks.
|
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
const std::map< int, ArBatteryMTX * > * ArRobot::getBatteryMap | ( | void | ) | const |
std::map< int, ArBatteryMTX * > * ArRobot::getBatteryMap | ( | void | ) |
|
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().
|
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().
ArRobot::ChargeState ArRobot::getChargeState | ( | void | ) | const |
Gets the charge state of the robot (see long docs)
unsigned int ArRobot::getConnectionCycleMultiplier | ( | void | ) | const |
Gets the multiplier for how many cycles ArRobot waits when connecting.
int ArRobot::getConnectionTimeoutTime | ( | void | ) | const |
Gets the time without a response until connection assumed lost.
Gets the number of seconds to go without response from the robot until it is assumed tha tthe connection with the robot has been broken and the disconnect on error events will happen.
|
inline |
Gets the legacy control heading.
Gets the control heading as an offset from the current heading... Note that this doesn't work in any modern firmware (uARCS, ARCOS, seekur, AmigoSH)
unsigned int ArRobot::getCycleTime | ( | void | ) | const |
Gets the number of ms between cycles.
Finds the number of milliseconds between cycles, at each cycle is when all packets are processed, all sensors are interpretted, all actions are called, and all user tasks are serviced.
Be warned, if you set this too small you could overflow your serial connection.
unsigned int ArRobot::getCycleWarningTime | ( | void | ) | const |
Gets the number of ms between cycles to warn over.
Sets a time such that if the number of milliseconds between cycles goes over this then there will be an ArLog::log(ArLog::Normal) warning.
unsigned int ArRobot::getCycleWarningTime | ( | void | ) |
Gets the number of ms between cycles to warn over.
Sets a time such that if the number of milliseconds between cycles goes over this then there will be an ArLog::log(ArLog::Normal) warning.
ArDeviceConnection * ArRobot::getDeviceConnection | ( | void | ) | const |
Gets the connection this instance uses.
Gets the connection this instance uses to the actual robot.
This is where commands will be sent and packets will be received from
unsigned int ArRobot::getDirectMotionPrecedenceTime | ( | void | ) | const |
Gets the length of time a direct motion command will take precedence over actions, in milliseconds.
The direct motion precedence time determines how long actions will be ignored after a direct motion command is given.
If the direct motion precedence time is 0, then direct motion will take precedence over actions until a clearDirectMotion command is issued. This value defaults to 0.
ArRetFunctor1< double, ArPoseWithTime > * ArRobot::getEncoderCorrectionCallback | ( | void | ) | const |
Gets the encoderCorrectionCallback.
This gets the encoderCorrectionCB, see setEncoderCorrectionCallback for details.
|
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.
|
inline |
Gets the encoder position the robot was at at the given timestamp.
|
inline |
Gets the encoder angular position ("theta") of the robot.
ArTransform ArRobot::getEncoderTransform | ( | void | ) | const |
Gets the encoder transform.
|
inline |
Gets the encoder X position of the robot.
|
inline |
Gets the encoder Y position of the robot.
int ArRobot::getIOAnalog | ( | int | num | ) | const |
Gets the n'th byte from the analog input data from the IO packet.
This gets the raw IO Analog value, which is a number between 0 and 1024 (2^10).
double ArRobot::getIOAnalogVoltage | ( | int | num | ) | const |
Gets the n'th byte from the analog input data from the IO packet.
This gets the IO Analog value converted to a voltage between 0 and 5 voltes.
unsigned char ArRobot::getIODigIn | ( | int | num | ) | const |
Gets the n'th byte from the digital input data from the IO packet.
unsigned char ArRobot::getIODigOut | ( | int | num | ) | const |
Gets the n'th byte from the digital output data from the IO packet.
const std::map< int, ArLaser * > * ArRobot::getLaserMap | ( | void | ) | const |
Gets the range device list.
std::map< int, ArLaser * > * ArRobot::getLaserMap | ( | void | ) |
ArTime ArRobot::getLastOdometryTime | ( | void | ) | const |
Gets the time the last odometry was received.
Get the time at which thet most recent SIP packet was received.
Whenever a SIP packet (aka "motor" packet) is received, this time is set to the receiption time minus the robot's reported internal odometry delay. The SIP provides robot position (see getPose()) and some other information (see robot manual for details).
ArTime ArRobot::getLastPacketTime | ( | void | ) | const |
Gets the time the last packet was received.
Get the time at which the most recent packet of any type was received This timestamp is updated whenever any packet is received from the robot.
double ArRobot::getLatAccel | ( | void | ) | const |
Gets the lateral acceleration.
double ArRobot::getLatDecel | ( | void | ) | const |
Gets the lateral acceleration.
|
inline |
Gets the current lateral velocity of the robot.
Note that this will only be valid if hasLatVel() returns true
double ArRobot::getLatVelMax | ( | void | ) | const |
Gets the maximum lateral velocity.
const std::map< int, ArLCDMTX * > * ArRobot::getLCDMap | ( | void | ) | const |
std::map< int, ArLCDMTX * > * ArRobot::getLCDMap | ( | void | ) |
long int ArRobot::getLeftEncoder | ( | void | ) |
Gets packet data from the left encoder.
|
inline |
This gets the total cumulative number of degrees the robot has turned (deg) This is a virtual odometer (by analogy with a car odometer) that measures the total linear distance the robot has travelled since ARIA connected, approximated by adding linear distance between current pose and previous pose in each ArRobot cycle.
|
inline |
This gets the total cumulative distance the robot has travelled (mm) This is a virtual odometer (by analogy with a car odometer) that measures the total linear distance the robot has travelled since ARIA connected, approximated by adding linear distance between current pose and previous pose in each ArRobot cycle.
|
inline |
Gets the delay in odometry readings.
This gets the odometry delay, not that this is just information about what the delay is it doesn't cause anything to happen in this class.
const ArRobotConfigPacketReader * ArRobot::getOrigRobotConfig | ( | void | ) | const |
Gets the original robot config packet information.
|
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.
|
inline |
Gets the position the robot was at at the given timestamp.
std::list< ArRangeDevice * > * ArRobot::getRangeDeviceList | ( | void | ) |
Gets the range device list.
This gets the list of range devices attached to this robot, do NOT manipulate this list directly.
If you want to manipulate use the appropriate addRangeDevice, or remRangeDevice
|
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.
|
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.)
|
inline |
Gets the instaneous battery voltage.
This is whatever the actual voltage of the robot is, if you want a value normalized to a common 12 volts for all robot types use getBatteryVoltage(). If the robot doesn't support this number the voltage will be less than 0 and you should use getBatteryVoltageNow().
long int ArRobot::getRightEncoder | ( | void | ) |
Gets packet data from the right encoder.
const ArRobotParams * ArRobot::getRobotParams | ( | void | ) | const |
Gets the parameters the robot is using.
ArRobotParams * ArRobot::getRobotParamsInternal | ( | void | ) |
|
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.
const std::map< int, ArSonarMTX * > * ArRobot::getSonarMap | ( | void | ) | const |
std::map< int, ArSonarMTX * > * ArRobot::getSonarMap | ( | void | ) |
int ArRobot::getSonarRange | ( | int | num | ) | const |
Gets the range of the last sonar reading for the given sonar.
num | the sonar number to check, should be between 0 and the number of sonar, the function won't fail if a bad number is given, will just return -1 |
ArSensorReading * ArRobot::getSonarReading | ( | int | num | ) | const |
Returns the sonar reading for the given sonar.
num | the sonar number to check, should be between 0 and the number of sonar, the function won't fail if a bad number is given, will just return false |
int ArRobot::getStabilizingTime | ( | void | ) | const |
How long we stabilize for in ms (0 means no stabilizng)
This is the amount of time the robot will stabilize for after it has connected to the robot (it won't report it is connected until after this time is over).
|
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 |
Gets the number of milliseconds between state reflection refreshes if the state has not changed.
The state reflection refresh time is the number of milliseconds between when the state reflector will refresh the robot, if the command hasn't changed.
The default is 500 milliseconds. If this number is less than the cyle time, it'll simply happen every cycle.
ArSyncTask * ArRobot::getSyncTaskRoot | ( | void | ) |
This gets the root of the syncronous task tree, only serious developers should use it.
This gets the root of the synchronous task tree, so that someone can add their own new types of tasks, or find out more information about each task...
only serious developers should use this.
|
inline |
Gets the global angular position ("theta") of the robot.
ArTransform ArRobot::getToGlobalTransform | ( | void | ) | const |
This gets the transform from local coords to global coords.
ArTransform ArRobot::getToLocalTransform | ( | void | ) | const |
This gets the transform for going from global coords to local coords.
|
inline |
This gets the number of degrees the robot has turned since the last time resetTripOdometer() was called (deg) This is a virtual odometer (by analogy with a car odometer) that measures the total linear distance the robot has travelled since first connected, or resetTripOdometer() was last called, approximated by adding linear distance between current pose and previous pose in each ArRobot cycle.
|
inline |
This gets the distance the robot has travelled since the last time resetTripOdometer() was called (mm) This is a virtual odometer that measures the total linear distance the robot has travelled since first connected, or resetTripOdometer() was called, approximated by adding linear distance between current pose and previous pose in each ArRobot cycle.
|
inline |
This gets the time since the "Trip Odometer" was reset (sec)
|
inline |
Gets the global X position of the robot.
|
inline |
Gets the global Y position of the robot.
bool ArRobot::hasBattery | ( | ArBatteryMTX * | device | ) | const |
Finds whether a particular battery is attached to this robot or not.
bool ArRobot::hasLaser | ( | ArLaser * | device | ) | const |
Finds whether a particular range device is attached to this robot or not.
|
inline |
Sees if the robot supports lateral velocities (e.g.
Seekur(TM))
bool ArRobot::hasLCD | ( | ArLCDMTX * | device | ) | const |
Finds whether a particular lcd is attached to this robot or not (MTX robots only)
bool ArRobot::hasRangeDevice | ( | ArRangeDevice * | device | ) | const |
Finds whether a particular range device is attached to this robot or not.
device | the device to check for |
bool ArRobot::hasSonar | ( | ArSonarMTX * | device | ) | const |
Finds whether a particular sonar is attached to this robot or not (MTX robots only)
|
inline |
Gets if the state of charge value is in use.
void ArRobot::init | ( | void | ) |
Internal function, shouldn't be used.
Sets up the packet handlers, sets up the sync list and makes the default priority resolver.
|
inline |
Questions whether the robot is connected or not.
bool ArRobot::isDirectMotion | ( | void | ) | const |
Returns true if direct motion commands are blocking actions.
Returns the state of direct motion commands: whether actions are allowed or not.
bool ArRobot::isHeadingDone | ( | double | delta = 0.0 | ) | const |
Sees if the robot is done changing to the previously given setHeading.
Determines if a setHeading() command is finished, to within a small distance.
If delta = 0 (default), the delta distance used is that which was set with setHeadingDoneDiff() (you can get that distnace value with getHeadingDoneDiff(), the default is 3).
delta | how close to the goal distance the robot must be |
bool ArRobot::isMoveDone | ( | double | delta = 0.0 | ) |
Sees if the robot is done moving the previously given move.
Determines if a move command is finished, to within a small distance threshold, "delta".
If delta = 0 (default), the delta distance set with setMoveDoneDist() will be used.
delta | how close to the goal distance the robot must be, or 0 for previously set default |
bool ArRobot::isRunning | ( | void | ) | const |
Returns whether the robot is currently running or not.
bool ArRobot::isSonarNew | ( | int | num | ) | const |
Find out if the given sonar reading was newly refreshed by the last incoming SIP received.
num | the sonar number to check, should be between 0 and the number of sonar, the function won't fail if a bad number is given, will just return false |
|
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.
bool ArRobot::loadParamFile | ( | const char * | file | ) |
Loads a parameter file (replacing all other params)
void ArRobot::logAllTasks | ( | void | ) | const |
Logs the list of all tasks, strictly for your viewing pleasure.
void ArRobot::logUserTasks | ( | void | ) | const |
Logs the list of user tasks, strictly for your viewing pleasure.
void ArRobot::loopOnce | ( | void | ) |
This function loops once... only serious developers should use it.
This function is only for serious developers, it basically runs the loop once.
You would use this function if you were wanting to use robot control in some other monolithic program, so you could work within its framework, rather than trying to get it to work in ARIA.
void ArRobot::move | ( | double | distance | ) |
Move the given distance forward/backwards.
Tells the robot to begin moving the specified distance forward/backwards.
ArRobot caches this value, and sends it during the next cycle (with a MOVE or VEL command, depending on the robot).
distance | the distance for the robot to move (millimeters). Note, due to the implementation of the MOVE command on some robots, it is best to restrict the distance to the range (5000mm, 5000mm] if possible. Not all robots have this restriction, however. |
void ArRobot::moveTo | ( | ArPose | pose, |
bool | doCumulative = true |
||
) |
Change stored pose (i.e. the value returned by getPose())
The robot-relative positions of the readings of attached range devices, plus sonar readings stored in this object, will also be updated.
pose | New pose to set (in absolute world coordinates) |
doCumulative | whether to update the cumulative buffers of range devices |
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).
poseTo | the new absolute real world position |
poseFrom | the original absolute real world position |
doCumulative | whether to update the cumulative buffers of range devices |
void ArRobot::packetHandlerNonThreaded | ( | void | ) |
Packet handler, internal, for use in the syncloop when there's no threading.
This is here for use if the robot is running without threading (some customers may use it that way, though we generally don't)
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.
void ArRobot::packetHandlerThreadedReader | ( | void | ) |
Packet handler, internal, for using from a thread to actually read all the packets.
This function gets called from the ArRobotPacketReaderThread, and does the actual reading of packets...
so that it their timing isn't affected by the rest of the sync loop
bool ArRobot::processMotorPacket | ( | ArRobotPacket * | packet | ) |
Processes a motor packet, internal.
MPL adding this so that each place the pose interpolation is used it doesn't have to account for the odometry delay
void ArRobot::processNewSonar | ( | char | number, |
int | range, | ||
ArTime | timeReceived | ||
) |
Processes a new sonar reading, internal.
This function used to just create more sonar readings if it didn't have the sonar number that was given (only the case if that sonar didn't have an entry in the param file), this caused some silent bugs in other peoples code and so was removed... especially since we don't know where the sonar are at if they weren't in the parameter file anyways.
bool ArRobot::remAction | ( | ArAction * | action | ) |
Removes an action from the list, by pointer.
Finds the action with the given pointer and removes it from the actions...
if more than one action has that pointer it find the one with the lowest priority
action | the action we want to remove |
bool ArRobot::remAction | ( | const char * | actionName | ) |
Removes an action from the list, by name.
Finds the action with the given name and removes it from the actions...
if more than one action has that name it find the one with the lowest priority
actionName | the name of the action we want to find |
bool ArRobot::remBattery | ( | ArBatteryMTX * | battery | ) |
Remove a battery from the robot's list, by instance (MTX robots only) Primarily for ARIA internal use only.
bool ArRobot::remBattery | ( | int | batteryNumber | ) |
Remove a battery from the robot's list, by number (MTX robots only) Primarily for ARIA internal use only.
void ArRobot::remConnectCB | ( | ArFunctor * | functor | ) |
Removes a connect callback.
functor | the functor to remove from the list of connect callbacks |
void ArRobot::remDisconnectNormallyCB | ( | ArFunctor * | functor | ) |
Removes a callback for when disconnect is called while connected.
functor | the functor to remove from the list of connect callbacks |
void ArRobot::remDisconnectOnErrorCB | ( | ArFunctor * | functor | ) |
Removes a callback for when disconnection happens because of an error.
functor | the functor to remove from the list of connect callbacks |
void ArRobot::remFailedConnectCB | ( | ArFunctor * | functor | ) |
Removes a callback for when a connection to the robot is failed.
functor | the functor to remove from the list of connect callbacks |
bool ArRobot::remLaser | ( | ArLaser * | laser, |
bool | removeAsRangeDevice = true |
||
) |
Remove a range device from the robot's list, by instance.
bool ArRobot::remLaser | ( | int | laserNumber, |
bool | removeAsRangeDevice = true |
||
) |
Remove a range device from the robot's list, by number.
bool ArRobot::remLCD | ( | ArLCDMTX * | lcd | ) |
Remove a lcd from the robot's list, by instance.
bool ArRobot::remLCD | ( | int | lcdNumber | ) |
Remove a lcd from the robot's list, by number.
void ArRobot::remPacketHandler | ( | ArRetFunctor1< bool, ArRobotPacket *> * | functor | ) |
Removes a packet handler from the list of packet handlers.
functor | the functor to remove from the list of packet handlers |
void ArRobot::remRangeDevice | ( | const char * | name | ) |
Remove a range device from the robot's list, by name.
name | remove the first device with this name |
void ArRobot::remRangeDevice | ( | ArRangeDevice * | device | ) |
Remove a range device from the robot's list, by instance.
device | remove the first device with this pointer value |
void ArRobot::remRunExitCB | ( | ArFunctor * | functor | ) |
Removes a callback for when the run loop exits for what ever reason.
functor | The functor to remove from the list of run exit callbacks |
void ArRobot::remSensorInterpTask | ( | const char * | name | ) |
Removes a sensor interp tasks by name.
void ArRobot::remSensorInterpTask | ( | ArFunctor * | functor | ) |
Removes a sensor interp tasks by functor.
bool ArRobot::remSonar | ( | ArSonarMTX * | sonar | ) |
Remove a sonar from the robot's list, by instance.
bool ArRobot::remSonar | ( | int | sonarNumber | ) |
Remove a sonar from the robot's list, by number.
void ArRobot::remStabilizingCB | ( | ArFunctor * | functor | ) |
Removes stabilizing callback.
functor | the functor to remove from the list of stabilizing callbacks |
void ArRobot::remUserTask | ( | const char * | name | ) |
Removes a user task from the list of synchronous taskes by name.
void ArRobot::remUserTask | ( | ArFunctor * | functor | ) |
Removes a user task from the list of synchronous taskes by functor.
void ArRobot::requestEncoderPackets | ( | void | ) |
Starts a continuous stream of encoder packets.
Encoder packet data is stored by ArRobot and can be read using getLeftEncoder() and getRightEncoder().
Encoder packets may be stopped with stopEncoderPackets().
Encoder packets are sent after the main SIP (motor packet) by ARCOS. If you want to handle encoder packets immediately upon reception, add a general robot packet handler to ArRobot with addPacketHandler(), and check the packet for the encoder packet ID 0x90. See addPacketHandler() for details on how to write a general packet handler.
void ArRobot::requestIOPackets | ( | void | ) |
Starts a continuous stream of IO packets.
void ArRobot::resetTripOdometer | ( | void | ) |
Resets the "Trip Odometer".
void ArRobot::run | ( | bool | stopRunIfNotConnected, |
bool | runNonThreaded = false |
||
) |
Starts the instance to do processing in this thread.
This starts the ongoing main loop, which invokes robot tasks until stopped.
This function does not return until the loop is stopped by a call to stopRunning(), or if 'true' is given for stopRunIfNotConnected, and the robot connection is closed or fails.
stopRunIfNotConnected | if true, the run will return if there is no connection to the robot at any given point, this is good for one-shot programs... if it is false the run won't return unless stop is called on the instance |
runNonThreaded | if true, the robot won't make the usual thread that it makes for reading the packets...you generally shouldn't use this, but it's provided in case folks are using programs without threading |
void ArRobot::runAsync | ( | bool | stopRunIfNotConnected, |
bool | runNonThreadedPacketReader = false |
||
) |
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
stopRunIfNotConnected | if true, the run will stop if there is no connection to the robot at any given point, this is good for one-shot programs. If false then the thread will continue until stopRunning() is called. |
runNonThreadedPacketReader | selects whether the packet reader object (receives and parses packets from the robot) should run in its own internal asychronous thread. Mostly for internal use. |
bool ArRobot::setAbsoluteMaxLatAccel | ( | double | maxAccel | ) |
Sets the robot's absolute maximum lateral acceleration.
This sets the absolute maximum lateral acceleration the robot will do...
the acceleration can also be set by the actions and by setLatAccel, but it will not be allowed to go higher than this value. You should not set this very often, if you want to manipulate this value you should use the actions or setLatAccel.
maxAccel | the maximum acceleration to be set, it must be a non-zero number |
bool ArRobot::setAbsoluteMaxLatDecel | ( | double | maxDecel | ) |
Sets the robot's absolute maximum lateral deceleration.
This sets the absolute maximum lateral deceleration the robot will do...
the deceleration can also be set by the actions and by setLatDecel, but it will not be allowed to go higher than this value. You should not set this very often, if you want to manipulate this value you should use the actions or setLatDecel.
maxDecel | the maximum deceleration to be set, it must be a non-zero number |
bool ArRobot::setAbsoluteMaxLatVel | ( | double | maxLatVel | ) |
Sets the robot's absolute maximum lateral velocity.
This sets the absolute maximum lateral velocity the robot will go...
the maximum velocity can also be set by the actions and by setLatVelMax, but it will not be allowed to go higher than this
value. You should not set this very often, if you want to manipulate this value you should use the actions or setLatVelMax.
maxLatVel | the maximum velocity to be set, it must be a non-zero number |
bool ArRobot::setAbsoluteMaxRotAccel | ( | double | maxAccel | ) |
Sets the robot's absolute maximum rotational acceleration.
This sets the absolute maximum rotational acceleration the robot will do...
the acceleration can also be set by the actions and by setRotAccel, but it will not be allowed to go higher than this value. You should not set this very often, if you want to manipulate this value you should use the actions or setRotAccel.
maxAccel | the maximum acceleration to be set, it must be a non-zero number |
bool ArRobot::setAbsoluteMaxRotDecel | ( | double | maxDecel | ) |
Sets the robot's absolute maximum rotational deceleration.
This sets the absolute maximum rotational deceleration the robot will do...
the deceleration can also be set by the actions and by setRotDecel, but it will not be allowed to go higher than this value. You should not set this very often, if you want to manipulate this value you should use the actions or setRotDecel.
maxDecel | the maximum deceleration to be set, it must be a non-zero number |
bool ArRobot::setAbsoluteMaxRotVel | ( | double | maxVel | ) |
Sets the robot's absolute maximum rotational velocity.
This sets the absolute maximum velocity the robot will go...
the maximum velocity can also be set by the actions and by setRotVelMax, but it will not be allowed to go higher than this value. You should not set this very often, if you want to manipulate this value you should use the actions or setRotVelMax.
maxVel | the maximum velocity to be set, it must be a non-zero number |
bool ArRobot::setAbsoluteMaxTransAccel | ( | double | maxAccel | ) |
Sets the robot's absolute maximum translational acceleration.
This sets the absolute maximum translational acceleration the robot will do...
the acceleration can also be set by the actions and by setTransAccel, but it will not be allowed to go higher than this value. You should not set this very often, if you want to manipulate this value you should use the actions or setTransAccel.
maxAccel | the maximum acceleration to be set, it must be a non-zero number |
bool ArRobot::setAbsoluteMaxTransDecel | ( | double | maxDecel | ) |
Sets the robot's absolute maximum translational deceleration.
This sets the absolute maximum translational deceleration the robot will do...
the deceleration can also be set by the actions and by setTransDecel, but it will not be allowed to go higher than this value. You should not set this very often, if you want to manipulate this value you should use the actions or setTransDecel.
maxDecel | the maximum deceleration to be set, it must be a non-zero number |
bool ArRobot::setAbsoluteMaxTransNegVel | ( | double | maxNegVel | ) |
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.
maxVel | the maximum velocity to be set, it must be a non-zero number and is in -mm/sec (use negative values) |
bool ArRobot::setAbsoluteMaxTransVel | ( | double | maxVel | ) |
Sets the robot's absolute maximum translational velocity.
This sets the absolute maximum velocity the robot will go...
the maximum velocity can also be set by the actions and by setTransVelMax, but it will not be allowed to go higher than this value. You should not set this very often, if you want to manipulate this value you should use the actions or setTransVelMax.
maxVel | the maximum velocity to be set, it must be a non-zero number and is in mm/sec |
void ArRobot::setConnectionCycleMultiplier | ( | unsigned int | multiplier | ) |
Sets the multiplier for how many cycles ArRobot waits when connecting.
multiplier | when the ArRobot is waiting for a connection packet back from a robot, it waits for this multiplier times the cycle time for the packet to come back before it gives up on it... This should be small for normal connections but if doing something over a slow network then you may want to make it larger |
void ArRobot::setConnectionTimeoutTime | ( | int | mSecs | ) |
Sets the time without a response until connection assumed lost.
Sets the number of milliseconds to go without a response from the robot until it is assumed that the connection with the robot has been broken and the disconnect on error events will happen.
Note that this will only happen with the default packet handler.
mSecs | if seconds is 0 then the connection timeout feature will be disabled, otherwise disconnect on error will be triggered after this number of seconds... |
void ArRobot::setCycleTime | ( | unsigned int | ms | ) |
Sets the number of ms between cycles.
Sets the number of milliseconds between cycles, at each cycle is when all packets are processed, all sensors are interpretted, all actions are called, and all user tasks are serviced.
Be warned, if you set this too small you could overflow your serial connection.
ms | the number of milliseconds between cycles |
void ArRobot::setCycleWarningTime | ( | unsigned int | ms | ) |
Sets the number of ms between cycles to warn over.
Sets a time such that if the number of milliseconds between cycles goes over this then there will be an ArLog::log(ArLog::Normal) warning.
ms | the number of milliseconds between cycles to warn over, 0 turns warning off |
void ArRobot::setDeadReconPose | ( | ArPose | pose | ) |
Sets the dead recon position of the robot.
pose | the position to set the dead recon position to |
void ArRobot::setDeltaHeading | ( | double | deltaHeading | ) |
Sets the delta heading.
Sets a delta heading to the robot, it caches this value, and sends it during the next cycle.
deltaHeading | the desired amount to change the heading of the robot by |
void ArRobot::setDeviceConnection | ( | ArDeviceConnection * | connection | ) |
Sets the connection this instance uses.
Sets the connection this instance uses to the actual robot.
This is where commands will be sent and packets will be received from
connection | The deviceConnection to use for this robot |
void ArRobot::setDirectMotionPrecedenceTime | ( | int | mSec | ) |
Sets the length of time a direct motion command will take precedence over actions, in milliseconds.
The direct motion precedence time determines how long actions will be ignored after a direct motion command is given.
If the direct motion precedence time is 0, then direct motion will take precedence over actions until a clearDirectMotion command is issued. This value defaults to 0.
mSec | the number of milliseconds direct movement should trump actions, if a negative number is given, then the value will be 0 |
void ArRobot::setEncoderCorrectionCallback | ( | ArRetFunctor1< double, ArPoseWithTime > * | functor | ) |
Sets the encoderCorrectionCallback.
This sets the encoderCorrectionCB, this callback returns the robots change in heading, it takes in the change in heading, x, and y, between the previous and current readings.
functor | an ArRetFunctor1 created as an ArRetFunctor1C, that will be the callback... call this function NULL to clear the callback |
Changes the transform.
This transform is applied to all odometric/encoder poses received.
If you simply want to transform the robot's final reported pose (as returned by getPose()) to match an external coordinate system, use moveTo() instead.
deadReconPos | the dead recon position to transform from |
globalPos | the real world global position to transform to |
void ArRobot::setEncoderTransform | ( | ArPose | transformPos | ) |
Changes the transform directly.
This transform is applied to all odometric/encoder poses received.
If you simply want to transform the robot's final reported pose (as returned by getPose()) to match an external coordinate system, use moveTo() instead.
transformPos | the position to transform to |
void ArRobot::setHeading | ( | double | heading | ) |
Sets the heading.
Sets the heading of the robot, it caches this value, and sends it during the next cycle.
heading | the desired heading of the robot (degrees) |
void ArRobot::setLatAccel | ( | double | acc | ) |
Sets the lateral acceleration.
void ArRobot::setLatDecel | ( | double | decel | ) |
Sets the lateral acceleration.
void ArRobot::setLatVel | ( | double | latVelocity | ) |
Sets the lateral velocity.
Sets the desired lateral (sideways on local Y axis) translational velocity of the robot.
ArRobot caches this value, and sends it with a LATVEL command during the next cycle. (Only has effect on robots that are capable of translating laterally, i.e. Seekur. Other robots will ignore the command.)
latVelocity | the desired translational velocity of the robot (mm/sec) |
void ArRobot::setLatVelMax | ( | double | vel | ) |
Sets the maximum lateral velocity.
|
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.
|
inline |
Sets if a config packet is requried or not...
By default it is not required, since some ancient robots have no config packets... some of the modern software may die hideously if there is no config packet, so you should set this to true if you're using modern robots (basically anything other than a pioneer 1)
void ArRobot::setRobotParams | ( | ArRobotParams * | params | ) |
Sets the robot to use a passed in set of params (passes ownership)
This function will take over ownership of the passed in params.
void ArRobot::setRotVel | ( | double | velocity | ) |
Sets the rotational velocity.
Sets the rotational velocity of the robot, it caches this value, and sends it during the next cycle.
velocity | the desired rotational velocity of the robot (deg/sec) |
void ArRobot::setStabilizingTime | ( | int | mSecs | ) |
How long we should stabilize for in ms (0 disables stabilizing)
This is the amount of time the robot will stabilize for after it has connected to the robot (it won't report it is connected until after this time is over).
By convention you should never set this lower than what you find the value at (though it will let you) this is so that everything can get itself stabilized before we let things drive.
mSecs | the amount of time to stabilize for (0 disables) |
void ArRobot::setStateReflectionRefreshTime | ( | int | mSec | ) |
Sets the number of milliseconds between state reflection refreshes if the state has not changed.
The state reflection refresh time is the number of milliseconds between when the state reflector will refresh the robot, if the command hasn't changed.
The default is 500 milliseconds. If this number is less than the cyle time, it'll simply happen every cycle.
mSec | the refresh time, in milliseconds, non-negative, if negative is given, then the value will be 0 |
void ArRobot::setVel | ( | double | velocity | ) |
Sets the velocity.
Sets the desired translational velocity of the robot.
ArRobot caches this value, and sends it with a VEL command during the next cycle.
velocity | the desired translational velocity of the robot (mm/sec) |
void ArRobot::setVel2 | ( | double | leftVelocity, |
double | rightVelocity | ||
) |
Sets the velocity of the wheels independently.
Sets the velocity of each of the wheels on the robot independently.
ArRobot caches these values, and sends them with a VEL2 command during the next cycle. Note that this cancels both translational velocity AND rotational velocity, and is canceled by any of the other direct motion commands.
leftVelocity | the desired velocity of the left wheel |
rightVelocity | the desired velocity of the right wheel |
void ArRobot::stateReflector | ( | void | ) |
State Reflector, internal.
MPL commenting out these lines, and making it so that if nothing is set it'll just stop
void ArRobot::stop | ( | void | ) |
Stops the robot.
Stops the robot, by telling it to have a translational velocity and rotational velocity of 0.
Also note that if you are using actions, this will cause the actions to be ignored until the direct motion precedence timeout has been exceeded or clearDirectMotion is called.
void ArRobot::stopEncoderPackets | ( | void | ) |
Stops a continuous stream of encoder packets.
void ArRobot::stopRunning | ( | bool | doDisconnect = true | ) |
Stops the robot from doing any more processing.
This stops this robot's processing cycle.
If it is running in a background thread (from runAsync()), it will cause that thread to exit. If it is running synchronously (from run()), then run() will return.
doDisconnect | If true, also disconnect from the robot connection (default is true). |
void ArRobot::stopStateReflection | ( | void | ) |
Sets the state reflection to be inactive (until motion or clearDirectMotion)
This stops the state reflection task from sending any motion commands to the robot (it still receives data from the robot, and it will still send the PULSE command).
If you later call clearDirectMotion(), then state reflection will be re-enabled, but the velocity values are reset to 0. Similarly, if you later use direct motion commands, state reflection for those commands will then become active and those commands will be sent each cycle; other commands will remain disabled. For example, if you call stopStateReflection(), then later use setTransVel(), then translation velocity commands will be re-enabled and used in state reflection, but rotational velocity will remain disabled until you call setRotVel(), or call clearDirectMotion().
ArRobot::WaitState ArRobot::waitForConnect | ( | unsigned int | msecs = 0 | ) |
Suspend calling thread until the ArRobot is connected.
This will suspend the calling thread until the ArRobot's run loop has managed to connect with the robot.
There is an optional paramater of milliseconds to wait for the ArRobot to connect. If msecs is set to 0, it will wait until the ArRobot connects. This function will never return if the robot can not be connected with. If you want to be able to handle that case within the calling thread, you must call waitForConnectOrConnFail().
msecs | milliseconds in which to wait for the ArRobot to connect |
ArRobot::WaitState ArRobot::waitForConnectOrConnFail | ( | unsigned int | msecs = 0 | ) |
Suspend calling thread until the ArRobot is connected or fails to connect.
This will suspend the calling thread until the ArRobot's run loop has managed to connect with the robot or fails to connect with the robot.
There is an optional paramater of milliseconds to wait for the ArRobot to connect. If msecs is set to 0, it will wait until the ArRobot connects.
msecs | milliseconds in which to wait for the ArRobot to connect |
ArRobot::WaitState ArRobot::waitForRunExit | ( | unsigned int | msecs = 0 | ) |
Suspend calling thread until the ArRobot run loop has exited.
This will suspend the calling thread until the ArRobot's run loop has exited.
There is an optional paramater of milliseconds to wait for the ArRobot run loop to exit . If msecs is set to 0, it will wait until the ArRrobot run loop exits.
msecs | milliseconds in which to wait for the robot to connect |
void ArRobot::wakeAllConnOrFailWaitingThreads | ( | ) |
Wake up all threads waiting for connection or connection failure.
This will wake all the threads waiting for the robot to be connected or waiting for the robot to fail to connect.
void ArRobot::wakeAllConnWaitingThreads | ( | ) |
Wake up all threads waiting for connection.
This will wake all the threads waiting for the robot to be connected.
void ArRobot::wakeAllRunExitWaitingThreads | ( | ) |
Wake up all threads waiting for the run loop to exit.
This will wake all the threads waiting for the run loop to exit.
void ArRobot::wakeAllWaitingThreads | ( | ) |
Wake up all threads waiting on this robot.
This will wake all the threads waiting for various major state changes in this particular ArRobot.
This includes all threads waiting for the robot to be connected and all threads waiting for the run loop to exit.