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

ArRobot.h

00001 /*
00002 MobileRobots Advanced Robotics Interface for Applications (ARIA)
00003 Copyright (C) 2004, 2005 ActivMedia Robotics LLC
00004 Copyright (C) 2006, 2007 MobileRobots Inc.
00005 
00006      This program is free software; you can redistribute it and/or modify
00007      it under the terms of the GNU General Public License as published by
00008      the Free Software Foundation; either version 2 of the License, or
00009      (at your option) any later version.
00010 
00011      This program is distributed in the hope that it will be useful,
00012      but WITHOUT ANY WARRANTY; without even the implied warranty of
00013      MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014      GNU General Public License for more details.
00015 
00016      You should have received a copy of the GNU General Public License
00017      along with this program; if not, write to the Free Software
00018      Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019 
00020 If you wish to redistribute ARIA under different terms, contact 
00021 MobileRobots for information about a commercial version of ARIA at 
00022 robots@mobilerobots.com or 
00023 MobileRobots Inc, 19 Columbia Drive, Amherst, NH 03031; 800-639-9481
00024 */
00025 
00026 #ifndef ARROBOT_H
00027 #define ARROBOT_H
00028 
00029 #include "ariaTypedefs.h"
00030 #include "ArRobotPacketSender.h"
00031 #include "ArRobotPacketReceiver.h"
00032 #include "ArFunctor.h"
00033 #include "ArFunctor.h"
00034 #include "ArSyncTask.h"
00035 #include "ArSensorReading.h"
00036 #include "ArMutex.h"
00037 #include "ArCondition.h"
00038 #include "ArSyncLoop.h"
00039 #include "ArRobotParams.h"
00040 #include "ArActionDesired.h"
00041 #include "ArResolver.h"
00042 #include "ArTransform.h"
00043 #include "ArInterpolation.h"
00044 #include "ArKeyHandler.h"
00045 #include <list>
00046 
00047 class ArAction;
00048 class ArRobotConfigPacketReader;
00049 class ArDeviceConnection;
00050 class ArRangeDevice;
00051 class ArRobotPacket;
00052 class ArPTZ;
00053 
00055 
00073 class ArRobot
00074 {
00075 public:
00076 
00077   typedef enum {
00078     WAIT_CONNECTED, 
00079     WAIT_FAILED_CONN, 
00080     WAIT_RUN_EXIT, 
00081     WAIT_TIMEDOUT, 
00082     WAIT_INTR, 
00083     WAIT_FAIL 
00084   } WaitState;
00085 
00086   enum ChargeState {
00087     CHARGING_UNKNOWN = -1,
00088     CHARGING_NOT = 0,
00089     CHARGING_BULK = 1,
00090     CHARGING_OVERCHARGE = 2,
00091     CHARGING_FLOAT = 3
00092   };
00094   AREXPORT ArRobot(const char * name = NULL, bool ignored = true,
00095            bool doSigHandle=true, 
00096            bool normalInit = true, bool addAriaExitCallback = true);
00097            
00099   AREXPORT ~ArRobot();
00100 
00102   AREXPORT void run(bool stopRunIfNotConnected);
00104   AREXPORT void runAsync(bool stopRunIfNotConnected);
00105 
00107   AREXPORT bool isRunning(void) const;
00108 
00110   AREXPORT void stopRunning(bool doDisconnect=true); 
00111 
00113   AREXPORT void setDeviceConnection(ArDeviceConnection *connection);
00115   AREXPORT ArDeviceConnection *getDeviceConnection(void) const;
00116   
00118 
00121   AREXPORT bool isConnected(void) const { return myIsConnected; }
00123   AREXPORT bool blockingConnect(void);
00125   AREXPORT bool asyncConnect(void);
00127   AREXPORT bool disconnect(void);
00128 
00130   AREXPORT void clearDirectMotion(void);
00132   AREXPORT bool isDirectMotion(void) const;
00133 
00136   AREXPORT void stopStateReflection(void);
00137   
00138 
00140   AREXPORT void enableMotors();
00142   AREXPORT void disableMotors();
00143 
00145   AREXPORT void enableSonar();
00147   AREXPORT void disableSonar();
00148 
00151   AREXPORT void stop(void);
00154   AREXPORT void setVel(double velocity);
00156   AREXPORT void setVel2(double leftVelocity, double rightVelocity);
00158   AREXPORT void move(double distance);
00160   AREXPORT bool isMoveDone(double delta = 0.0);
00162   AREXPORT void setMoveDoneDist(double dist) { myMoveDoneDist = dist; }
00164   AREXPORT double getMoveDoneDist(void) { return myMoveDoneDist; }
00166   AREXPORT void setHeading(double heading);
00168   AREXPORT void setRotVel(double velocity);
00170   AREXPORT void setDeltaHeading(double deltaHeading);
00172   AREXPORT bool isHeadingDone(double delta = 0.0) const;
00174   AREXPORT void setHeadingDoneDiff(double degrees) 
00175     { myHeadingDoneDiff = degrees; }
00177   AREXPORT double getHeadingDoneDiff(void) const { return myHeadingDoneDiff; }
00178 
00179 
00182   AREXPORT void setDirectMotionPrecedenceTime(int mSec);
00183 
00186   AREXPORT unsigned int getDirectMotionPrecedenceTime(void) const;
00187 
00189   AREXPORT bool com(unsigned char command);
00191   AREXPORT bool comInt(unsigned char command, short int argument);
00193   AREXPORT bool com2Bytes(unsigned char command, char high, char low);
00195   AREXPORT bool comStr(unsigned char command, const char *argument);
00197   AREXPORT bool comStrN(unsigned char command, const char *str, int size);
00199   AREXPORT bool comDataN(unsigned char command, const char *data, int size);
00200 
00202   AREXPORT const char * getRobotName(void) const { return myRobotName.c_str();}
00204   AREXPORT const char * getRobotType(void) const { return myRobotType.c_str();}
00206   AREXPORT const char * getRobotSubType(void) const 
00207     { return myRobotSubType.c_str(); }
00208 
00210   AREXPORT double getAbsoluteMaxTransVel(void) const 
00211     { return myAbsoluteMaxTransVel; }
00213   AREXPORT bool setAbsoluteMaxTransVel(double maxVel);
00214 
00216   AREXPORT double getAbsoluteMaxTransAccel(void) const 
00217     { return myAbsoluteMaxTransAccel; }
00219   AREXPORT bool setAbsoluteMaxTransAccel(double maxAccel);
00220 
00222   AREXPORT double getAbsoluteMaxTransDecel(void) const 
00223     { return myAbsoluteMaxTransDecel; }
00225   AREXPORT bool setAbsoluteMaxTransDecel(double maxDecel);
00226 
00228   AREXPORT double getAbsoluteMaxRotVel(void) const 
00229     { return myAbsoluteMaxRotVel; }
00231   AREXPORT bool setAbsoluteMaxRotVel(double maxVel);
00232   
00234   AREXPORT double getAbsoluteMaxRotAccel(void) const 
00235     { return myAbsoluteMaxRotAccel; }
00237   AREXPORT bool setAbsoluteMaxRotAccel(double maxAccel);
00238 
00240   AREXPORT double getAbsoluteMaxRotDecel(void) const 
00241     { return myAbsoluteMaxRotDecel; }
00243   AREXPORT bool setAbsoluteMaxRotDecel(double maxDecel);
00244 
00245 
00246   // Accessors
00247 
00255   ArPose getPose(void) const { return myGlobalPose; }
00257   double getX(void) const { return  myGlobalPose.getX(); }
00259   double getY(void) const { return myGlobalPose.getY(); }
00261   double getTh(void) const { return myGlobalPose.getTh(); }
00263   double findDistanceTo(const ArPose pose) 
00264     { return myGlobalPose.findDistanceTo(pose); }
00266   double findAngleTo(const ArPose pose) 
00267     { return myGlobalPose.findAngleTo(pose); }
00269   double findDeltaHeadingTo(const ArPose pose) 
00270     { return ArMath::subAngle(myGlobalPose.findAngleTo(pose),
00271                   myGlobalPose.getTh()); }
00272 
00273 
00275   double getVel(void) const { return myVel; }
00277 
00283   double getRotVel(void) const { return myRotVel; }
00285   double getRobotRadius(void) const { return myParams->getRobotRadius(); }
00287   double getRobotWidth(void) const { return myParams->getRobotWidth(); }
00289   double getRobotLength(void) const { return myParams->getRobotLength(); }
00291   double getRobotLengthFront(void) const { return myRobotLengthFront; }
00293   double getRobotLengthRear(void) const { return myRobotLengthRear; }
00295   double getRobotDiagonal(void) const { return myParams->getRobotDiagonal(); }
00297 
00306   double getBatteryVoltage(void) const {return myBatteryAverager.getAverage();}
00308 
00312   double getBatteryVoltageNow(void) const { return myBatteryVoltage; }
00314 
00327   double getRealBatteryVoltage(void) const 
00328     { return myRealBatteryAverager.getAverage(); }
00330 
00336   double getRealBatteryVoltageNow(void) const { return myRealBatteryVoltage; }
00338   double getLeftVel(void) const { return myLeftVel; }
00340   double getRightVel(void) const { return myRightVel; }
00342   int getStallValue(void) const { return myStallValue; }
00344   bool isLeftMotorStalled(void) const 
00345     { return (myStallValue & 0xff) & ArUtil::BIT0; }
00347   bool isRightMotorStalled(void) const
00348     { return ((myStallValue & 0xff00) >> 8) & ArUtil::BIT0; }
00350 
00354   double getControl(void) const { return myControl; }
00356   int getFlags(void) const { return myFlags; }
00358   int getFaultFlags(void) const { return myFaultFlags; }
00360   bool hasFaultFlags(void) const { return myHasFaultFlags; }
00362   bool areMotorsEnabled(void) const { return (myFlags & ArUtil::BIT0); }
00364   bool areSonarsEnabled(void) const { 
00365     return (myFlags & 
00366         (ArUtil::BIT1 | ArUtil::BIT2 | ArUtil::BIT3 | ArUtil::BIT4)); }
00368   bool isEStopPressed(void) const { return (myFlags & ArUtil::BIT5); }
00370   double getCompass(void) const { return myCompass; }
00372   int getAnalogPortSelected(void) const { return myAnalogPortSelected; }
00374   unsigned char getAnalog(void) const { return myAnalog; }
00376   unsigned char getDigIn(void) const { return myDigIn; }
00378   unsigned char getDigOut(void) const { return myDigOut; }
00380   AREXPORT ChargeState getChargeState(void) const;
00381 
00383   int getIOAnalogSize(void) const { return myIOAnalogSize; }
00385   int getIODigInSize(void) const { return myIODigInSize; }
00387   int getIODigOutSize(void) const { return myIODigOutSize; }
00388 
00390   AREXPORT int getIOAnalog(int num) const;
00392   AREXPORT double getIOAnalogVoltage(int num) const;
00394   AREXPORT unsigned char getIODigIn(int num) const;
00396   AREXPORT unsigned char getIODigOut(int num) const;
00397 
00399   bool hasTableSensingIR(void) const { return myParams->haveTableSensingIR(); }
00401   AREXPORT bool isLeftTableSensingIRTriggered(void) const;
00403   AREXPORT bool isRightTableSensingIRTriggered(void) const;
00405   AREXPORT bool isLeftBreakBeamTriggered(void) const;
00407   AREXPORT bool isRightBreakBeamTriggered(void) const;
00409   ArTime getIOPacketTime(void) const { return myLastIOPacketReceivedTime; }
00410 
00412   AREXPORT bool getEstop(void) { return (myFlags & ArUtil::BIT5); }
00413 
00415   bool hasFrontBumpers(void) const { return myParams->haveFrontBumpers(); }
00417   unsigned int getNumFrontBumpers(void) const 
00418     { return myParams->numFrontBumpers(); }
00420   bool hasRearBumpers(void) const { return myParams->haveRearBumpers(); }
00422   unsigned int getNumRearBumpers(void) const 
00423     { return myParams->numRearBumpers(); }
00424 
00430   ArPose getEncoderPose(void) const { return myEncoderPose; }
00431 
00433 
00442   bool isTryingToMove(void) { return myTryingToMove; }
00444 
00450   void forceTryingToMove(void) { myTryingToMove = true; }
00451   
00452 
00454   AREXPORT int getMotorPacCount(void) const;
00456   AREXPORT int getSonarPacCount(void) const;
00457 
00459   AREXPORT int getSonarRange(int num) const;
00461   AREXPORT bool isSonarNew(int num) const;
00463   AREXPORT int getNumSonar(void) const { return myNumSonar; }
00465   AREXPORT ArSensorReading *getSonarReading(int num) const;
00467   AREXPORT int getClosestSonarRange(double startAngle, double endAngle) const;
00469   AREXPORT int getClosestSonarNumber(double startAngle, double endAngle) const;
00470 
00472   AREXPORT const char *getName(void) const;
00474   AREXPORT void setName(const char *name);
00475 
00477   AREXPORT void moveTo(ArPose pose, bool doCumulative = true);
00479   AREXPORT void moveTo(ArPose to, ArPose from, bool doCumulative = true);
00480 
00482   size_t getBatteryVoltageAverageOfNum(void) 
00483     { return myBatteryAverager.getNumToAverage(); }
00484 
00486   void setBatteryVoltageAverageOfNum(size_t numToAverage)
00487     { myBatteryAverager.setNumToAverage(numToAverage); }
00488 
00490   size_t getRealBatteryVoltageAverageOfNum(void) 
00491     { return myRealBatteryAverager.getNumToAverage(); }
00492 
00494   void setRealBatteryVoltageAverageOfNum(size_t numToAverage)
00495     { myRealBatteryAverager.setNumToAverage(numToAverage); }
00496 
00498   AREXPORT void requestEncoderPackets(void);
00499 
00501   AREXPORT void requestIOPackets(void);
00502 
00504   AREXPORT void stopEncoderPackets(void);
00505 
00507   AREXPORT void stopIOPackets(void);
00508 
00510   AREXPORT long int getLeftEncoder(void);
00511 
00513   AREXPORT long int getRightEncoder(void);
00514 
00516   AREXPORT void setEncoderTransform(ArPose deadReconPos,
00517                     ArPose globalPos);
00518 
00520   AREXPORT void setEncoderTransform(ArPose transformPos);
00521 
00523   AREXPORT ArTransform getEncoderTransform(void) const;
00524 
00526   AREXPORT ArTransform getToGlobalTransform(void) const;
00527 
00529   AREXPORT ArTransform getToLocalTransform(void) const;
00530 
00532   AREXPORT void applyTransform(ArTransform trans, bool doCumulative = true);
00533 
00535   AREXPORT void setDeadReconPose(ArPose pose);
00536 
00538   AREXPORT double getOdometerDistance(void) { return myOdometerDistance; }
00539 
00541   AREXPORT double getOdometerDegrees(void) { return myOdometerDegrees; }
00542 
00544   AREXPORT double getOdometerTime(void) { return myOdometerStart.secSince(); }
00545 
00547   AREXPORT void resetOdometer(void);
00548 
00550   AREXPORT void addRangeDevice(ArRangeDevice *device);
00552   AREXPORT void remRangeDevice(const char *name);
00554   AREXPORT void remRangeDevice(ArRangeDevice *device);
00555 
00557   AREXPORT const ArRangeDevice *findRangeDevice(const char *name) const;
00558 
00560   AREXPORT ArRangeDevice *findRangeDevice(const char *name);
00561 
00563   AREXPORT std::list<ArRangeDevice *> *getRangeDeviceList(void);
00564 
00566   AREXPORT bool hasRangeDevice(ArRangeDevice *device) const;
00567 
00569   AREXPORT double checkRangeDevicesCurrentPolar(
00570       double startAngle, double endAngle, double *angle = NULL,
00571       const ArRangeDevice **rangeDevice = NULL,
00572       bool useLocationDependentDevices = true) const;
00573 
00575   AREXPORT double checkRangeDevicesCumulativePolar(
00576       double startAngle, double endAngle, double *angle = NULL,
00577       const ArRangeDevice **rangeDevice = NULL,
00578       bool useLocationDependentDevices = true) const;
00579 
00580 
00581   // Goes through all the range devices and checks them
00582   AREXPORT double checkRangeDevicesCurrentBox(
00583       double x1, double y1, double x2, double y2,
00584       ArPose *readingPos = NULL,
00585       const ArRangeDevice **rangeDevice = NULL,
00586       bool useLocationDependentDevices = true) const;
00587 
00588   // Goes through all the range devices and checks them
00589   AREXPORT double checkRangeDevicesCumulativeBox(
00590       double x1, double y1, double x2, double y2,
00591       ArPose *readingPos = NULL, 
00592       const ArRangeDevice **rangeDevice = NULL,
00593       bool useLocationDependentDevices = true) const;
00594 
00596   void setPTZ(ArPTZ *ptz) { myPtz = ptz; }
00598   ArPTZ *getPTZ(void) { return myPtz; }
00599 
00602   AREXPORT void setStateReflectionRefreshTime(int msec);
00603 
00606   AREXPORT int getStateReflectionRefreshTime(void) const;
00607 
00609   AREXPORT void addPacketHandler(
00610       ArRetFunctor1<bool, ArRobotPacket *> *functor, 
00611       ArListPos::Pos position = ArListPos::LAST);
00612   
00614   AREXPORT void remPacketHandler(
00615       ArRetFunctor1<bool, ArRobotPacket *> *functor);
00616 
00618   AREXPORT void addConnectCB(ArFunctor *functor, 
00619                  ArListPos::Pos position = ArListPos::LAST);
00621   AREXPORT void remConnectCB(ArFunctor *functor);
00622 
00624   AREXPORT void addFailedConnectCB(ArFunctor *functor, 
00625                    ArListPos::Pos position = ArListPos::LAST);
00627   AREXPORT void remFailedConnectCB(ArFunctor *functor);
00628 
00630   AREXPORT void addDisconnectNormallyCB(ArFunctor *functor, 
00631                 ArListPos::Pos position = ArListPos::LAST);
00633   AREXPORT void remDisconnectNormallyCB(ArFunctor *functor);
00634   
00636   AREXPORT void addDisconnectOnErrorCB(ArFunctor *functor, 
00637                    ArListPos::Pos position = ArListPos::LAST);
00639   AREXPORT void remDisconnectOnErrorCB(ArFunctor *functor);
00640 
00642   AREXPORT void addRunExitCB(ArFunctor *functor, 
00643                  ArListPos::Pos position = ArListPos::LAST);
00645   AREXPORT void remRunExitCB(ArFunctor *functor);
00646 
00648   AREXPORT WaitState waitForConnect(unsigned int msecs=0);
00650   AREXPORT WaitState waitForConnectOrConnFail(unsigned int msecs=0);
00652   AREXPORT WaitState waitForRunExit(unsigned int msecs=0);
00653 
00655   AREXPORT void wakeAllWaitingThreads();
00657   AREXPORT void wakeAllConnWaitingThreads();
00659   AREXPORT void wakeAllConnOrFailWaitingThreads();
00661   AREXPORT void wakeAllRunExitWaitingThreads();
00662 
00664   AREXPORT bool addUserTask(const char *name, int position, 
00665                    ArFunctor *functor,
00666                    ArTaskState::State *state = NULL);
00668   AREXPORT void remUserTask(const char *name);
00670   AREXPORT void remUserTask(ArFunctor *functor);
00671 
00673   AREXPORT ArSyncTask *findUserTask(const char *name);
00675   AREXPORT ArSyncTask *findUserTask(ArFunctor *functor);
00676   
00678   AREXPORT void logUserTasks(void) const;
00680   AREXPORT void logAllTasks(void) const;
00681 
00683   AREXPORT bool addSensorInterpTask(const char *name, int position, 
00684                        ArFunctor *functor,
00685                            ArTaskState::State *state = NULL);
00687   AREXPORT void remSensorInterpTask(const char *name);
00689   AREXPORT void remSensorInterpTask(ArFunctor *functor);
00690 
00692   AREXPORT ArSyncTask *findTask(const char *name);
00694   AREXPORT ArSyncTask *findTask(ArFunctor *functor);
00695 
00697   AREXPORT bool addAction(ArAction *action, int priority);
00699   AREXPORT bool remAction(ArAction *action);
00701   AREXPORT bool remAction(const char *actionName);
00703   AREXPORT ArAction *findAction(const char *actionName);
00706   AREXPORT ArResolver::ActionMap *getActionMap(void);
00708   AREXPORT void deactivateActions(void);
00709 
00711   AREXPORT void logActions(bool logDeactivated = false) const;
00712 
00714   AREXPORT ArResolver *getResolver(void);
00715 
00717   AREXPORT void setResolver(ArResolver *resolver);
00718 
00720   AREXPORT void setEncoderCorrectionCallback(
00721       ArRetFunctor1<double, ArPoseWithTime> *functor);
00723   AREXPORT ArRetFunctor1<double, ArPoseWithTime> *
00724           getEncoderCorrectionCallback(void) const;
00725 
00726   // set up some of the internals of how the ArRobot class works
00728   AREXPORT void setCycleTime(unsigned int ms);
00730   AREXPORT unsigned int getCycleTime(void) const;
00732   AREXPORT void setCycleWarningTime(unsigned int ms);
00734   AREXPORT unsigned int getCycleWarningTime(void) const;
00736   AREXPORT unsigned int getCycleWarningTime(void);
00738   AREXPORT void setConnectionCycleMultiplier(unsigned int multiplier);
00740   AREXPORT unsigned int getConnectionCycleMultiplier(void) const;
00741   
00743   void setCycleChained(bool cycleChained) { myCycleChained = cycleChained; }
00745   bool isCycleChained(void) const { return myCycleChained; }
00747   AREXPORT void setConnectionTimeoutTime(int mSecs);
00749   AREXPORT int getConnectionTimeoutTime(void) const;
00751   AREXPORT ArTime getLastPacketTime(void) const;
00752 
00754   AREXPORT void setPoseInterpNumReadings(size_t numReadings) 
00755     { myInterpolation.setNumberOfReadings(numReadings); }
00756 
00758   AREXPORT size_t getPoseInterpNumReadings(void) const
00759     { return myInterpolation.getNumberOfReadings(); }
00760 
00762 
00764   AREXPORT int getPoseInterpPosition(ArTime timeStamp, ArPose *position)
00765     { return myInterpolation.getPose(timeStamp, position); }
00766 
00768   AREXPORT void setEncoderPoseInterpNumReadings(size_t numReadings) 
00769     { myEncoderInterpolation.setNumberOfReadings(numReadings); }
00770 
00772   AREXPORT size_t getEncoderPoseInterpNumReadings(void) const
00773     { return myEncoderInterpolation.getNumberOfReadings(); }
00774 
00776 
00778   AREXPORT int getEncoderPoseInterpPosition(ArTime timeStamp, ArPose *position)
00779     { return myEncoderInterpolation.getPose(timeStamp, position); }
00780 
00782   AREXPORT unsigned int getCounter(void) const { return myCounter; }
00783 
00785   AREXPORT const ArRobotParams *getRobotParams(void) const;
00786 
00788   AREXPORT const ArRobotConfigPacketReader *getOrigRobotConfig(void) const;
00789 
00791   AREXPORT void setTransVelMax(double vel);
00793   AREXPORT void setTransAccel(double acc);
00795   AREXPORT void setTransDecel(double decel);
00797   AREXPORT void setRotVelMax(double vel);
00799   AREXPORT void setRotAccel(double acc);
00801   AREXPORT void setRotDecel(double decel);
00802 
00804   bool hasSettableVelMaxes(void) const 
00805     { return myParams->hasSettableVelMaxes(); }
00807   AREXPORT double getTransVelMax(void) const;
00809   AREXPORT double getRotVelMax(void) const;
00811   bool hasSettableAccsDecs(void)
00812       const { return myParams->hasSettableAccsDecs(); }
00814   AREXPORT double getTransAccel(void) const;
00816   AREXPORT double getTransDecel(void) const;
00818   AREXPORT double getRotAccel(void) const;
00820   AREXPORT double getRotDecel(void) const;
00821 
00823   AREXPORT bool loadParamFile(const char *file);
00824 
00826   AREXPORT void attachKeyHandler(ArKeyHandler *keyHandler,
00827                  bool exitOnEscape = true,
00828                  bool useExitNotShutdown = true);
00830   AREXPORT ArKeyHandler *getKeyHandler(void) const;
00831 
00833   AREXPORT int lock() {return(myMutex.lock());}
00835   AREXPORT int tryLock() {return(myMutex.tryLock());}
00837   AREXPORT int unlock() {return(myMutex.unlock());}
00838 
00840   AREXPORT bool isStabilizing(void) { return myIsStabilizing; }
00841 
00843   AREXPORT void setStabilizingTime(int mSecs);
00844 
00846   AREXPORT int getStabilizingTime(void) const;
00847 
00848 
00850   AREXPORT void addStabilizingCB(ArFunctor *functor, 
00851                  ArListPos::Pos position = ArListPos::LAST);
00853   AREXPORT void remStabilizingCB(ArFunctor *functor);
00854   
00857   AREXPORT ArSyncTask *getSyncTaskRoot(void);
00858 
00860   AREXPORT void loopOnce(void);
00861 
00863 
00868   AREXPORT void setOdometryDelay(int msec) { myOdometryDelay = msec; }
00869 
00871 
00876   AREXPORT int getOdometryDelay(void) { return myOdometryDelay; }
00877 
00879   AREXPORT bool getLogMovementSent(void) { return myLogMovementSent; }
00881   AREXPORT void setLogMovementSent(bool logMovementSent)
00882     { myLogMovementSent = logMovementSent; }
00883 
00885   AREXPORT bool getLogMovementReceived(void) { return myLogMovementReceived; }
00887   AREXPORT void setLogMovementReceived(bool logMovementReceived)
00888     { myLogMovementReceived = logMovementReceived; }
00889 
00891   AREXPORT bool getLogVelocitiesReceived(void) 
00892     { return myLogVelocitiesReceived; }
00894   AREXPORT void setLogVelocitiesReceived(bool logVelocitiesReceived) 
00895     { myLogVelocitiesReceived = logVelocitiesReceived; }
00896 
00898   AREXPORT bool getPacketsReceivedTracking(void)
00899     { return myPacketsReceivedTracking; }
00901   AREXPORT void setPacketsReceivedTracking(bool packetsReceivedTracking);
00902 
00904   AREXPORT bool getPacketsSentTracking(void)
00905     { return myPacketsSentTracking; }
00907   AREXPORT void setPacketsSentTracking(bool packetsSentTracking)
00908     { myPacketsSentTracking = packetsSentTracking; }
00909 
00911   AREXPORT bool getLogActions(void) { return myLogActions; }
00913   AREXPORT void setLogActions(bool logActions)
00914   { myLogActions = logActions; }
00915 
00916   
00918   AREXPORT void incCounter(void) { myCounter++; }
00919 
00921   AREXPORT void packetHandler(void);
00923   AREXPORT void actionHandler(void);
00925   AREXPORT void stateReflector(void);
00927   AREXPORT void robotLocker(void);
00929   AREXPORT void robotUnlocker(void);
00930 
00932   AREXPORT void keyHandlerExit(void);
00933 
00935   AREXPORT bool processMotorPacket(ArRobotPacket *packet);
00937   AREXPORT void processNewSonar(char number, int range, ArTime timeReceived);
00939   AREXPORT bool processEncoderPacket(ArRobotPacket *packet);
00941   AREXPORT bool processIOPacket(ArRobotPacket *packet);
00942   
00944   AREXPORT void init(void);
00945 
00947   AREXPORT void setUpSyncList(void);
00949   AREXPORT void setUpPacketHandlers(void);
00950 
00951   ArRetFunctor1C<bool, ArRobot, ArRobotPacket *> myMotorPacketCB;
00952   ArRetFunctor1C<bool, ArRobot, ArRobotPacket *> myEncoderPacketCB;
00953   ArRetFunctor1C<bool, ArRobot, ArRobotPacket *> myIOPacketCB;
00954   ArFunctorC<ArRobot> myPacketHandlerCB;
00955   ArFunctorC<ArRobot> myActionHandlerCB;
00956   ArFunctorC<ArRobot> myStateReflectorCB;
00957   ArFunctorC<ArRobot> myRobotLockerCB;
00958   ArFunctorC<ArRobot> myRobotUnlockerCB;
00959   ArFunctorC<ArRobot> myKeyHandlerExitCB;
00960   ArFunctorC<ArKeyHandler> *myKeyHandlerCB;
00961 
00962   // These four are internal... only people monkeying deeply should mess
00963   // with them, so they aren't documented... these process the cblists
00964   // and such
00966   AREXPORT int asyncConnectHandler(bool tryHarderToConnect);
00967 
00969   AREXPORT void dropConnection(void);
00971   AREXPORT void failedConnect(void);
00973   AREXPORT bool madeConnection(void);
00975   AREXPORT void startStabilization(void);
00977   AREXPORT void finishedConnection(void);
00979   AREXPORT void cancelConnection(void);
00980 
00983   AREXPORT bool handlePacket(ArRobotPacket *packet);
00985   AREXPORT std::list<ArFunctor *> * getRunExitListCopy();
00987   AREXPORT void processParamFile(void);
00988 
00997   AREXPORT ArPose getRawEncoderPose(void) const { return myRawEncoderPose; }
00998 
01000   AREXPORT bool getNoTimeWarningThisCycle(void)  
01001     { return myNoTimeWarningThisCycle; }
01003   AREXPORT void setNoTimeWarningThisCycle(bool noTimeWarningThisCycle)  
01004     { myNoTimeWarningThisCycle = noTimeWarningThisCycle; }
01005   // callbacks for warning time and if we should warn now to pass to sync tasks
01006   ArRetFunctorC<unsigned int, ArRobot> myGetCycleWarningTimeCB;
01007   ArRetFunctorC<bool, ArRobot> myGetNoTimeWarningThisCycleCB;
01009   AREXPORT void ariaExitCallback(void);
01011   void setConnectWithNoParams(bool connectWithNoParams) 
01012     { myConnectWithNoParams = connectWithNoParams; }
01013 protected:
01014   enum RotDesired { 
01015     ROT_NONE,
01016     ROT_IGNORE,
01017     ROT_HEADING,
01018     ROT_VEL
01019   };
01020   enum TransDesired {
01021     TRANS_NONE,
01022     TRANS_IGNORE,
01023     TRANS_VEL,
01024     TRANS_VEL2,
01025     TRANS_DIST,
01026     TRANS_DIST_NEW
01027   };
01028   void reset(void);
01029  
01030 
01031   // the config the robot had at connection
01032   ArRobotConfigPacketReader *myOrigRobotConfig;
01033   // the values we'll maintain for the different motion parameters
01034   double myRotVelMax;
01035   double myRotAccel;
01036   double myRotDecel;
01037   double myTransVelMax;
01038   double myTransAccel;
01039   double myTransDecel;
01040 
01041   ArPTZ *myPtz;
01042   bool myNoTimeWarningThisCycle;
01043 
01044   long int myLeftEncoder;
01045   long int myRightEncoder;
01046   bool myFirstEncoderPose;
01047   ArPoseWithTime myRawEncoderPose;
01048 
01049   ArTransform myEncoderTransform;
01050 
01051   bool myLogMovementSent;
01052   bool myLogMovementReceived;
01053   bool myPacketsReceivedTracking;
01054   bool myLogActions;
01055   bool myLogVelocitiesReceived;
01056   double myLastVel;
01057   double myLastRotVel;
01058   double myLastHeading;
01059   double myLastCalculatedRotVel;
01060 
01061   bool myTryingToMove;
01062 
01063   long myPacketsReceivedTrackingCount;
01064   ArTime myPacketsReceivedTrackingStarted;
01065   bool myPacketsSentTracking;
01066   ArMutex myMutex;
01067   ArSyncTask *mySyncTaskRoot;
01068   std::list<ArRetFunctor1<bool, ArRobotPacket *> *> myPacketHandlerList;
01069 
01070   ArSyncLoop mySyncLoop;
01071 
01072   std::list<ArFunctor *> myStabilizingCBList;
01073   std::list<ArFunctor *> myConnectCBList;
01074   std::list<ArFunctor *> myFailedConnectCBList;
01075   std::list<ArFunctor *> myDisconnectNormallyCBList;
01076   std::list<ArFunctor *> myDisconnectOnErrorCBList;
01077   std::list<ArFunctor *> myRunExitCBList;
01078 
01079   ArRetFunctor1<double, ArPoseWithTime> *myEncoderCorrectionCB;
01080   std::list<ArRangeDevice *> myRangeDeviceList;
01081 
01082   ArCondition myConnectCond;
01083   ArCondition myConnOrFailCond;
01084   ArCondition myRunExitCond;
01085 
01086   ArResolver::ActionMap myActions;
01087   bool myOwnTheResolver;
01088   ArResolver *myResolver;
01089 
01090   std::map<int, ArSensorReading *> mySonars;
01091   int myNumSonar;
01092   
01093   unsigned int myCounter;
01094   bool myIsConnected;
01095   bool myIsStabilizing;
01096 
01097   bool myBlockingConnectRun;
01098   bool myAsyncConnectFlag;
01099   int myAsyncConnectState;
01100   int myAsyncConnectNoPacketCount;
01101   int myAsyncConnectTimesTried;
01102   ArTime myAsyncStartedConnection;
01103   int myAsyncConnectStartBaud;
01104   ArTime myAsyncConnectStartedChangeBaud;
01105   bool myAsyncConnectSentChangeBaud;
01106   ArTime myStartedStabilizing;
01107 
01108   int myStabilizingTime;
01109 
01110   bool mySentPulse;
01111 
01112   double myTransVal;
01113   double myTransVal2;
01114   int myLastTransVal;
01115   int myLastTransVal2;
01116   TransDesired myTransType;
01117   TransDesired myLastTransType;
01118   ArTime myTransSetTime;
01119   ArTime myLastTransSent;
01120   int myLastActionTransVal;
01121   bool myActionTransSet;
01122   ArPose myTransDistStart;
01123   double myMoveDoneDist;
01124 
01125   double myRotVal;
01126   int myLastRotVal;
01127   RotDesired myRotType;
01128   RotDesired myLastRotType;
01129   ArTime myRotSetTime;
01130   ArTime myLastRotSent;
01131   int myLastActionRotVal;
01132   bool myLastActionRotHeading;
01133   bool myLastActionRotStopped;
01134   bool myActionRotSet;
01135   double myHeadingDoneDiff;
01136 
01137   double myLastSentTransVelMax;
01138   double myLastSentTransAccel;
01139   double myLastSentTransDecel;
01140   double myLastSentRotVelMax;
01141   double myLastSentRotAccel;
01142   double myLastSentRotDecel;
01143 
01144   ArTime myLastPulseSent;
01145 
01146   int myDirectPrecedenceTime;
01147   
01148   int myStateReflectionRefreshTime;
01149 
01150   ArActionDesired myActionDesired;
01151 
01152   std::string myName;
01153   std::string myRobotName;
01154   std::string myRobotType;
01155   std::string myRobotSubType;
01156 
01157   double myAbsoluteMaxTransVel;
01158   double myAbsoluteMaxTransAccel;
01159   double myAbsoluteMaxTransDecel;
01160   double myAbsoluteMaxRotVel;
01161   double myAbsoluteMaxRotAccel;
01162   double myAbsoluteMaxRotDecel;
01163 
01164   ArDeviceConnection *myConn;
01165 
01166   ArRobotPacketSender mySender;
01167   ArRobotPacketReceiver myReceiver;
01168 
01169   ArRobotParams *myParams;
01170   double myRobotLengthFront;
01171   double myRobotLengthRear;
01172 
01173   ArInterpolation myInterpolation;
01174   ArInterpolation myEncoderInterpolation;
01175 
01176   ArKeyHandler *myKeyHandler;
01177   bool myKeyHandlerUseExitNotShutdown;
01178 
01179   bool myConnectWithNoParams;
01180   bool myWarnedAboutExtraSonar;
01181 
01182   // variables for tracking the data stream
01183   time_t myTimeLastMotorPacket;
01184   int myMotorPacCurrentCount;
01185   int myMotorPacCount;
01186   time_t myTimeLastSonarPacket;
01187   int mySonarPacCurrentCount;
01188   int mySonarPacCount;
01189   unsigned int myCycleTime;
01190   unsigned int myCycleWarningTime;
01191   unsigned int myConnectionCycleMultiplier;
01192   bool myCycleChained;
01193   ArTime myLastPacketReceivedTime;
01194   int myTimeoutTime;
01195 
01196   bool myRequestedIOPackets;
01197   bool myRequestedEncoderPackets;
01198 
01199   // all the state reflecing variables
01200   ArPoseWithTime myEncoderPose;
01201   ArTime myEncoderPoseTaken;
01202   ArPose myGlobalPose;
01203   // um, this myEncoderGlobalTrans doesn't do anything
01204   ArTransform myEncoderGlobalTrans;
01205   double myLeftVel;
01206   double myRightVel;
01207   double myBatteryVoltage;
01208   ArRunningAverage myBatteryAverager;
01209   double myRealBatteryVoltage;
01210   ArRunningAverage myRealBatteryAverager;
01211   int myStallValue;
01212   double myControl;
01213   int myFlags;
01214   int myFaultFlags;
01215   bool myHasFaultFlags;
01216   double myCompass;
01217   int myAnalogPortSelected;
01218   unsigned char myAnalog;
01219   unsigned char myDigIn;
01220   unsigned char myDigOut;
01221   int myIOAnalog[128];
01222   unsigned char myIODigIn[255];
01223   unsigned char myIODigOut[255];
01224   int myIOAnalogSize;
01225   int myIODigInSize;
01226   int myIODigOutSize;
01227   ArTime myLastIOPacketReceivedTime;
01228   double myVel;
01229   double myRotVel;
01230   int myLastX;
01231   int myLastY;
01232   int myLastTh;
01233   ChargeState myChargeState;
01234 
01235   double myOdometerDistance;
01236   double myOdometerDegrees;
01237   ArTime myOdometerStart;
01238 
01239   int myOdometryDelay;
01240 
01241   bool myAddedAriaExitCB;
01242   ArFunctorC<ArRobot> myAriaExitCB;
01243 };
01244 
01245 
01246 #endif // ARROBOT_H

Generated on Tue Feb 20 10:51:41 2007 for Aria by  doxygen 1.4.0