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

ArModes.cpp

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 #include "ArExport.h"
00027 #include "ariaOSDef.h"
00028 #include "ArMode.h"
00029 #include "ArModes.h"
00030 #include "ArKeyHandler.h"
00031 #include "ArSonyPTZ.h"
00032 #include "ArVCC4.h"
00033 #include "ArDPPTU.h"
00034 #include "ArAMPTU.h"
00035 #include "ArSick.h"
00036 #include "ArAnalogGyro.h"
00037 #include "ArRobotConfigPacketReader.h"
00038 #include "ariaInternal.h"
00039 
00040 AREXPORT ArModeTeleop::ArModeTeleop(ArRobot *robot, const char *name, char key, char key2): 
00041   ArMode(robot, name, key, key2),
00042   myGroup(robot)
00043 {
00044   myGroup.deactivate();
00045 }
00046 
00047 AREXPORT ArModeTeleop::~ArModeTeleop()
00048 {
00049   
00050 }
00051 
00052 AREXPORT void ArModeTeleop::activate(void)
00053 {
00054   if (!baseActivate())
00055     return;
00056   myGroup.activateExclusive();
00057 }
00058 
00059 AREXPORT void ArModeTeleop::deactivate(void)
00060 {
00061   if (!baseDeactivate())
00062     return;
00063   myGroup.deactivate();
00064 }
00065 
00066 AREXPORT void ArModeTeleop::help(void)
00067 {
00068   ArLog::log(ArLog::Terse, 
00069        "Teleop mode will drive under your joystick or keyboard control.");
00070   ArLog::log(ArLog::Terse, 
00071          "It will not allow you to drive into obstacles it can see,");
00072   ArLog::log(ArLog::Terse, 
00073       "though if you are presistent you may be able to run into something.");
00074   ArLog::log(ArLog::Terse, "For joystick, hold in the trigger button and then move the joystick to drive.");
00075   ArLog::log(ArLog::Terse, "For keyboard control these are the keys and their actions:");
00076   ArLog::log(ArLog::Terse, "%13s:  speed up if forward or no motion, slow down if going backwards", "up arrow");
00077   ArLog::log(ArLog::Terse, "%13s:  slow down if going forwards, speed up if backward or no motion", "down arrow");
00078   ArLog::log(ArLog::Terse, "%13s:  turn left", "left arrow");
00079   ArLog::log(ArLog::Terse, "%13s:  turn right", "right arrow");
00080   ArLog::log(ArLog::Terse, "%13s:  stop", "space bar");
00081   printf("%10s %10s %10s %10s %10s %10s\n", "transVel", "rotVel", "x", "y", "th", "volts");
00082 }
00083 
00084 AREXPORT void ArModeTeleop::userTask(void)
00085 {
00086   printf("\r%10.0f %10.0f %10.0f %10.0f %10.1f %10.1f", myRobot->getVel(), 
00087      myRobot->getRotVel(), myRobot->getX(), myRobot->getY(), 
00088      myRobot->getTh(), myRobot->getRealBatteryVoltage());
00089 }
00090 
00091 AREXPORT ArModeUnguardedTeleop::ArModeUnguardedTeleop(ArRobot *robot,
00092                               const char *name, 
00093                               char key, char key2): 
00094   ArMode(robot, name, key, key2),
00095   myGroup(robot)
00096 {
00097   myGroup.deactivate();
00098 }
00099 
00100 AREXPORT ArModeUnguardedTeleop::~ArModeUnguardedTeleop()
00101 {
00102   
00103 }
00104 
00105 AREXPORT void ArModeUnguardedTeleop::activate(void)
00106 {
00107   if (!baseActivate())
00108     return;
00109   myGroup.activateExclusive();
00110 }
00111 
00112 AREXPORT void ArModeUnguardedTeleop::deactivate(void)
00113 {
00114   if (!baseDeactivate())
00115     return;
00116   myGroup.deactivate();
00117 }
00118 
00119 AREXPORT void ArModeUnguardedTeleop::help(void)
00120 {
00121   ArLog::log(ArLog::Terse, 
00122        "Unguarded teleop mode will drive under your joystick or keyboard control.");
00123   ArLog::log(ArLog::Terse, 
00124          "\n### THIS MODE IS UNGUARDED AND UNSAFE, BE CAREFUL DRIVING");
00125   ArLog::log(ArLog::Terse,
00126          "\nAs it will allow you to drive into things or down stairs.");
00127   ArLog::log(ArLog::Terse, "For joystick, hold in the trigger button and then move the joystick to drive.");
00128   ArLog::log(ArLog::Terse, "For keyboard control these are the keys and their actions:");
00129   ArLog::log(ArLog::Terse, "%13s:  speed up if forward or no motion, slow down if going backwards", "up arrow");
00130   ArLog::log(ArLog::Terse, "%13s:  slow down if going forwards, speed up if backward or no motion", "down arrow");
00131   ArLog::log(ArLog::Terse, "%13s:  turn left", "left arrow");
00132   ArLog::log(ArLog::Terse, "%13s:  turn right", "right arrow");
00133   ArLog::log(ArLog::Terse, "%13s:  stop", "space bar");
00134   printf("%10s %10s %10s %10s %10s %10s\n", "transVel", "rotVel", "x", "y", "th", "volts");
00135 }
00136 
00137 AREXPORT void ArModeUnguardedTeleop::userTask(void)
00138 {
00139   printf("\r%10.0f %10.0f %10.0f %10.0f %10.1f %10.1f", myRobot->getVel(), 
00140      myRobot->getRotVel(), myRobot->getX(), myRobot->getY(), 
00141      myRobot->getTh(), myRobot->getRealBatteryVoltage());
00142 }
00143 
00144 AREXPORT ArModeWander::ArModeWander(ArRobot *robot, const char *name, char key, char key2): 
00145   ArMode(robot, name, key, key2),
00146   myGroup(robot)
00147 {
00148   myGroup.deactivate();
00149 }
00150 
00151 AREXPORT ArModeWander::~ArModeWander()
00152 {
00153   
00154 }
00155 
00156 AREXPORT void ArModeWander::activate(void)
00157 {
00158   if (!baseActivate())
00159     return;
00160   myGroup.activateExclusive();
00161 }
00162 
00163 AREXPORT void ArModeWander::deactivate(void)
00164 {
00165   if (!baseDeactivate())
00166     return;
00167   myGroup.deactivate(); 
00168 }
00169 
00170 AREXPORT void ArModeWander::help(void)
00171 {
00172   ArLog::log(ArLog::Terse, "Wander mode will simply drive around forwards until it finds an obstacle,");
00173   ArLog::log(ArLog::Terse, "then it will turn until its clear, and continue.");
00174   printf("%10s %10s %10s %10s %10s %10s\n", "transVel", "rotVel", "x", "y", "th", "volts");
00175 }
00176 
00177 AREXPORT void ArModeWander::userTask(void)
00178 {
00179   printf("\r%10.0f %10.0f %10.0f %10.0f %10.1f %10.1f", myRobot->getVel(), 
00180      myRobot->getRotVel(), myRobot->getX(), myRobot->getY(), 
00181      myRobot->getTh(), myRobot->getRealBatteryVoltage());
00182 }
00183 
00184 AREXPORT ArModeGripper::ArModeGripper(ArRobot *robot, const char *name, 
00185                       char key, char key2): 
00186   ArMode(robot, name, key, key2),
00187   myGripper(robot),
00188   myOpenCB(this, &ArModeGripper::open),
00189   myCloseCB(this, &ArModeGripper::close),
00190   myUpCB(this, &ArModeGripper::up),
00191   myDownCB(this, &ArModeGripper::down),
00192   myStopCB(this, &ArModeGripper::stop),
00193   myExerciseCB(this, &ArModeGripper::exercise)
00194 {
00195   myExercising = false;
00196 }
00197 
00198 AREXPORT ArModeGripper::~ArModeGripper()
00199 {
00200   
00201 }
00202 
00203 AREXPORT void ArModeGripper::activate(void)
00204 {
00205   if (!baseActivate())
00206     return;
00207 
00208   addKeyHandler(ArKeyHandler::UP, &myUpCB);
00209   addKeyHandler(ArKeyHandler::DOWN, &myDownCB);
00210   addKeyHandler(ArKeyHandler::RIGHT, &myOpenCB);
00211   addKeyHandler(ArKeyHandler::LEFT, &myCloseCB);  
00212   addKeyHandler(ArKeyHandler::SPACE, &myStopCB);
00213   addKeyHandler('e', &myExerciseCB);
00214   addKeyHandler('E', &myExerciseCB);
00215 }
00216 
00217 AREXPORT void ArModeGripper::deactivate(void)
00218 {
00219   if (!baseDeactivate())
00220     return;
00221 
00222   remKeyHandler(&myUpCB);
00223   remKeyHandler(&myDownCB);
00224   remKeyHandler(&myOpenCB);
00225   remKeyHandler(&myCloseCB);
00226   remKeyHandler(&myStopCB);
00227   remKeyHandler(&myExerciseCB);
00228 }
00229 
00230 AREXPORT void ArModeGripper::userTask(void)
00231 {
00232   int val;
00233   printf("\r");
00234   if (myGripper.getBreakBeamState() & 2) // outer 
00235     printf("%13s", "blocked");
00236   else 
00237     printf("%13s", "clear");
00238   if (myGripper.getBreakBeamState() & 1) // inner
00239     printf("%13s", "blocked");
00240   else 
00241     printf("%13s", "clear");
00242   val = myGripper.getGripState(); // gripper portion
00243   if (val == 0)
00244     printf("%13s", "between");
00245   else if (val == 1)
00246     printf("%13s", "open");
00247   else if (val == 2)
00248     printf("%13s", "closed");
00249   if (myGripper.isLiftMaxed()) // lift
00250     printf("%13s", "maxed");
00251   else
00252     printf("%13s", "clear");
00253   val = myGripper.getPaddleState(); // paddle section
00254   if (val & 1) // left paddle
00255     printf("%13s", "triggered");
00256   else
00257     printf("%13s", "clear");
00258   if (val & 2) // right paddle
00259     printf("%13s", "triggered");
00260   else
00261     printf("%13s", "clear");
00262   // exercise the thing
00263   if (myExercising)
00264   {
00265     switch (myExerState) {
00266     case UP_OPEN:
00267       if ((myLastExer.mSecSince() > 3000 && myGripper.isLiftMaxed()) ||
00268       myLastExer.mSecSince() > 30000)
00269       {
00270     myGripper.gripClose();
00271     myExerState = UP_CLOSE;
00272     myLastExer.setToNow();
00273     if (myLastExer.mSecSince() > 30000)
00274       ArLog::log(ArLog::Terse, "\nLift took more than thirty seconds to raise, there is probably a problem with it.\n");
00275       }
00276       break;
00277     case UP_CLOSE:
00278       if (myGripper.getGripState() == 2 || myLastExer.mSecSince() > 10000)
00279       {
00280     myGripper.liftDown();
00281     myExerState = DOWN_CLOSE;
00282     myLastExer.setToNow();
00283     if (myLastExer.mSecSince() > 10000)
00284       ArLog::log(ArLog::Terse, "\nGripper took more than 10 seconds to close, there is probably a problem with it.\n");
00285       }
00286       break;
00287     case DOWN_CLOSE:
00288       if ((myLastExer.mSecSince() > 3000 && myGripper.isLiftMaxed()) ||
00289       myLastExer.mSecSince() > 30000)
00290       {
00291     myGripper.gripOpen();
00292     myExerState = DOWN_OPEN;
00293     myLastExer.setToNow();
00294     if (myLastExer.mSecSince() > 30000)
00295       ArLog::log(ArLog::Terse, "\nLift took more than thirty seconds to raise, there is probably a problem with it.\n");
00296       }
00297       break;
00298     case DOWN_OPEN:
00299       if (myGripper.getGripState() == 1 || myLastExer.mSecSince() > 10000)
00300       {
00301     myGripper.liftUp();
00302     myExerState = UP_OPEN;
00303     myLastExer.setToNow();
00304     if (myLastExer.mSecSince() > 10000)
00305       ArLog::log(ArLog::Terse, "\nGripper took more than 10 seconds to open, there is probably a problem with it.\n");
00306       }
00307       break;
00308     }      
00309     
00310   }
00311 }
00312 
00313 AREXPORT void ArModeGripper::open(void)
00314 {
00315   if (myExercising == true)
00316   {
00317     myExercising = false;
00318     myGripper.gripperHalt();
00319   }
00320   myGripper.gripOpen();
00321 }
00322 
00323 AREXPORT void ArModeGripper::close(void)
00324 {
00325   if (myExercising == true)
00326   {
00327     myExercising = false;
00328     myGripper.gripperHalt();
00329   }
00330   myGripper.gripClose();
00331 }
00332 
00333 AREXPORT void ArModeGripper::up(void)
00334 {
00335   if (myExercising == true)
00336   {
00337     myExercising = false;
00338     myGripper.gripperHalt();
00339   }
00340   myGripper.liftUp();
00341 }
00342 
00343 AREXPORT void ArModeGripper::down(void)
00344 {
00345   if (myExercising == true)
00346   {
00347     myExercising = false;
00348     myGripper.gripperHalt();
00349   }
00350   myGripper.liftDown();
00351 }
00352 
00353 AREXPORT void ArModeGripper::stop(void)
00354 {
00355   if (myExercising == true)
00356   {
00357     myExercising = false;
00358     myGripper.gripperHalt();
00359   }
00360   myGripper.gripperHalt();
00361 }
00362 
00363 AREXPORT void ArModeGripper::exercise(void)
00364 {
00365   if (myExercising == false)
00366   {
00367     ArLog::log(ArLog::Terse, 
00368        "\nGripper will now be exercised until another command is given.");
00369     myExercising = true;
00370     myExerState = UP_OPEN;
00371     myGripper.liftUp();
00372     myGripper.gripOpen();
00373     myLastExer.setToNow();
00374   }
00375 }
00376 
00377 AREXPORT void ArModeGripper::help(void)
00378 {
00379   ArLog::log(ArLog::Terse, 
00380          "Gripper mode will let you control or exercise the gripper.");
00381   ArLog::log(ArLog::Terse, 
00382       "If you start exercising the gripper it will stop your other commands.");
00383   ArLog::log(ArLog::Terse, 
00384          "If you use other commands it will interrupt the exercising.");
00385   ArLog::log(ArLog::Terse, "%13s:  raise lift", "up arrow");
00386   ArLog::log(ArLog::Terse, "%13s:  lower lift", "down arrow");
00387   ArLog::log(ArLog::Terse, "%13s:  close gripper paddles", "left arrow");
00388   ArLog::log(ArLog::Terse, "%13s:  open gripper paddles", "right arrow");
00389   ArLog::log(ArLog::Terse, "%13s:  stop gripper paddles and lift", 
00390          "space bar");
00391   ArLog::log(ArLog::Terse, "%13s:  exercise the gripper", "'e' or 'E'");
00392   ArLog::log(ArLog::Terse, "\nGripper status:");
00393   ArLog::log(ArLog::Terse, "%13s%13s%13s%13s%13s%13s", "BB outer", "BB inner",
00394          "Paddles", "Lift", "LeftPaddle", "RightPaddle");
00395   
00396 }
00397 
00398 
00399 
00400 AREXPORT ArModeCamera::ArModeCamera(ArRobot *robot, const char *name, 
00401                       char key, char key2): 
00402   ArMode(robot, name, key, key2),
00403   myUpCB(this, &ArModeCamera::up),
00404   myDownCB(this, &ArModeCamera::down),
00405   myLeftCB(this, &ArModeCamera::left),
00406   myRightCB(this, &ArModeCamera::right),
00407   myCenterCB(this, &ArModeCamera::center),
00408   myZoomInCB(this, &ArModeCamera::zoomIn),  
00409   myZoomOutCB(this, &ArModeCamera::zoomOut),
00410   myExerciseCB(this, &ArModeCamera::exercise),
00411   mySonyCB(this, &ArModeCamera::sony),
00412   myCanonCB(this, &ArModeCamera::canon),
00413   myDpptuCB(this, &ArModeCamera::dpptu),
00414   myAmptuCB(this, &ArModeCamera::amptu),
00415   myCanonInvertedCB(this, &ArModeCamera::canonInverted),
00416   mySonySerialCB(this, &ArModeCamera::sonySerial),
00417   myCanonSerialCB(this, &ArModeCamera::canonSerial),
00418   myDpptuSerialCB(this, &ArModeCamera::dpptuSerial),
00419   myAmptuSerialCB(this, &ArModeCamera::amptuSerial),
00420   myCanonInvertedSerialCB(this, &ArModeCamera::canonInvertedSerial),
00421   myCom1CB(this, &ArModeCamera::com1),
00422   myCom2CB(this, &ArModeCamera::com2),
00423   myCom3CB(this, &ArModeCamera::com3),
00424   myCom4CB(this, &ArModeCamera::com4),
00425   myAux1CB(this, &ArModeCamera::aux1),
00426   myAux2CB(this, &ArModeCamera::aux2)
00427 {
00428   myState = STATE_CAMERA;
00429   myExercising = false;
00430 }
00431 
00432 AREXPORT ArModeCamera::~ArModeCamera()
00433 {
00434   
00435 }
00436 
00437 AREXPORT void ArModeCamera::activate(void)
00438 {
00439   ArKeyHandler *keyHandler;
00440   if (!baseActivate())
00441     return;
00442   // see if there is already a keyhandler, if not something is wrong
00443   // (since constructor should make one if there isn't one yet
00444   if ((keyHandler = Aria::getKeyHandler()) == NULL)
00445   {
00446     ArLog::log(ArLog::Terse,"ArModeCamera::activate: There should already be a key handler, but there isn't... mode won't work");
00447     return;
00448   }
00449   if (myState == STATE_CAMERA)
00450     takeCameraKeys();
00451   else if (myState == STATE_PORT)
00452     takePortKeys();
00453   else if (myState == STATE_MOVEMENT)
00454     takeMovementKeys();
00455   else
00456     ArLog::log(ArLog::Terse,"ArModeCamera in bad state.");
00457   
00458 }
00459 
00460 AREXPORT void ArModeCamera::deactivate(void)
00461 {
00462   if (!baseDeactivate())
00463     return;
00464   if (myState == STATE_CAMERA)
00465     giveUpCameraKeys();
00466   else if (myState == STATE_PORT)
00467     giveUpPortKeys();
00468   else if (myState == STATE_MOVEMENT)
00469     giveUpMovementKeys();
00470   else
00471     ArLog::log(ArLog::Terse,"ArModeCamera in bad state.");
00472 }
00473 
00474 AREXPORT void ArModeCamera::userTask(void)
00475 {
00476   if (myExercising && myCam != NULL && myLastExer.mSecSince() > 10000)
00477   {
00478     switch (myExerState) {
00479     case CENTER:
00480       myCam->panTilt(myCam->getMaxNegPan(), myCam->getMaxPosTilt());
00481       myExerState = UP_LEFT;
00482       myLastExer.setToNow();
00483       break;
00484     case UP_LEFT:
00485       myCam->panTilt(myCam->getMaxPosPan(), myCam->getMaxPosTilt());
00486       myExerState = UP_RIGHT;
00487       myLastExer.setToNow();
00488       break;
00489     case UP_RIGHT:
00490       myCam->panTilt(myCam->getMaxPosPan(), myCam->getMaxNegTilt());
00491       myExerState = DOWN_RIGHT;
00492       myLastExer.setToNow();
00493       break;
00494     case DOWN_RIGHT:
00495       myCam->panTilt(myCam->getMaxNegPan(), myCam->getMaxNegTilt());
00496       myExerState = DOWN_LEFT;
00497       myLastExer.setToNow();
00498       break;
00499     case DOWN_LEFT:
00500       myCam->panTilt(0, 0);
00501       myExerState = CENTER;
00502       myLastExer.setToNow();
00503       break;
00504     }      
00505   }
00506   if (myExercising && myCam != NULL && myCam->canZoom() && 
00507       myLastExerZoomed.mSecSince() > 35000)
00508   {
00509     if (myExerZoomedIn)
00510       myCam->zoom(myCam->getMinZoom());
00511     else
00512       myCam->zoom(myCam->getMaxZoom());
00513     myLastExerZoomed.setToNow();
00514   }
00515 }
00516 
00517 AREXPORT void ArModeCamera::left(void)
00518 {
00519   if (myExercising == true)
00520     myExercising = false;
00521   myCam->panRel(-5);
00522 }
00523 
00524 AREXPORT void ArModeCamera::right(void)
00525 {
00526   if (myExercising == true)
00527     myExercising = false;
00528   myCam->panRel(5);
00529 }
00530 
00531 AREXPORT void ArModeCamera::up(void)
00532 {
00533   if (myExercising == true)
00534     myExercising = false;
00535   myCam->tiltRel(3);
00536 }
00537 
00538 AREXPORT void ArModeCamera::down(void)
00539 {  
00540   if (myExercising == true)
00541     myExercising = false;
00542   myCam->tiltRel(-3);
00543 }
00544 
00545 AREXPORT void ArModeCamera::center(void)
00546 {
00547   if (myExercising == true)
00548     myExercising = false;
00549   myCam->panTilt(0, 0);
00550   myCam->zoom(myCam->getMinZoom());
00551 }
00552 
00553 AREXPORT void ArModeCamera::exercise(void)
00554 {
00555   if (myExercising == false)
00556   {
00557     ArLog::log(ArLog::Terse, 
00558        "Camera will now be exercised until another command is given.");
00559     myExercising = true;
00560     myExerState = UP_LEFT;
00561     myLastExer.setToNow();
00562     myCam->panTilt(myCam->getMaxNegPan(), myCam->getMaxPosTilt());
00563     myLastExerZoomed.setToNow();
00564     myExerZoomedIn = true;
00565     if (myCam->canZoom())
00566       myCam->zoom(myCam->getMaxZoom());
00567   }
00568 }
00569 
00570 AREXPORT void ArModeCamera::help(void)
00571 {
00572   ArLog::log(ArLog::Terse, 
00573          "Camera mode will let you control or exercise the camera.");
00574   ArLog::log(ArLog::Terse, 
00575       "If you start exercising the camera it will stop your other commands.");
00576   if (myState == STATE_CAMERA)
00577     helpCameraKeys();
00578   else if (myState == STATE_PORT)
00579     helpPortKeys();
00580   else if (myState == STATE_MOVEMENT)
00581     helpMovementKeys();
00582   else
00583     ArLog::log(ArLog::Terse, "Something is horribly wrong and mode camera is in no state.");
00584 }
00585 
00586 AREXPORT void ArModeCamera::zoomIn(void)
00587 {
00588   if (myCam->canZoom())
00589   {
00590     myCam->zoom(myCam->getZoom() + 
00591      ArMath::roundInt((myCam->getMaxZoom() - myCam->getMinZoom()) * .01));
00592   }
00593 }
00594 
00595 AREXPORT void ArModeCamera::zoomOut(void)
00596 {
00597   if (myCam->canZoom())
00598   {
00599     myCam->zoom(myCam->getZoom() - 
00600     ArMath::roundInt((myCam->getMaxZoom() - myCam->getMinZoom()) * .01));
00601   }
00602 }
00603 
00604 AREXPORT void ArModeCamera::sony(void)
00605 {
00606   myCam = new ArSonyPTZ(myRobot);
00607   ArLog::log(ArLog::Terse, "\nSony selected, now need to select the aux port.");
00608   cameraToAux();
00609 }
00610 
00611 AREXPORT void ArModeCamera::canon(void)
00612 {
00613   myCam = new ArVCC4(myRobot);
00614   ArLog::log(ArLog::Terse, "\nCanon selected, now need to select the aux port.");
00615   cameraToAux();
00616 }
00617 
00618 AREXPORT void ArModeCamera::dpptu(void)
00619 {
00620   myCam = new ArDPPTU(myRobot);
00621   ArLog::log(ArLog::Terse, "\nDPPTU selected, now need to select the aux port.");
00622   cameraToAux();
00623 }
00624 
00625 AREXPORT void ArModeCamera::amptu(void)
00626 {
00627   myCam = new ArAMPTU(myRobot);
00628   ArLog::log(ArLog::Terse, 
00629          "\nActivMedia Pan Tilt Unit selected, now need to select the aux port.");
00630   cameraToAux();
00631 }
00632 
00633 AREXPORT void ArModeCamera::canonInverted(void)
00634 {
00635   myCam = new ArVCC4(myRobot, true);
00636   ArLog::log(ArLog::Terse, "\nInverted Canon selected, now need to select the aux port.");
00637   cameraToAux();
00638 }
00639 
00640 AREXPORT void ArModeCamera::sonySerial(void)
00641 {
00642   myCam = new ArSonyPTZ(myRobot);
00643   ArLog::log(ArLog::Terse, "\nSony selected, now need to select serial port.");
00644   cameraToPort();
00645 }
00646 
00647 AREXPORT void ArModeCamera::canonSerial(void)
00648 {
00649   myCam = new ArVCC4(myRobot);
00650   ArLog::log(ArLog::Terse, 
00651          "\nCanon VCC4 selected, now need to select serial port.");
00652   cameraToPort();
00653 }
00654 
00655 AREXPORT void ArModeCamera::dpptuSerial(void)
00656 {
00657   myCam = new ArDPPTU(myRobot);
00658   ArLog::log(ArLog::Terse, "\nDPPTU selected, now need to select serial port.");
00659   cameraToPort();
00660 }
00661 
00662 AREXPORT void ArModeCamera::amptuSerial(void)
00663 {
00664   myCam = new ArAMPTU(myRobot);
00665   ArLog::log(ArLog::Terse, "\nAMPTU selected, now need to select serial port.");
00666   cameraToPort();
00667 }
00668 
00669 AREXPORT void ArModeCamera::canonInvertedSerial(void)
00670 {
00671   myCam = new ArVCC4(myRobot, true);
00672   ArLog::log(ArLog::Terse, 
00673          "\nInverted Canon VCC4 selected, now need to select serial port.");
00674   cameraToPort();
00675 }
00676 
00677 AREXPORT void ArModeCamera::com1(void)
00678 {
00679   myConn.setPort(ArUtil::COM1);
00680   portToMovement();
00681 }
00682 
00683 AREXPORT void ArModeCamera::com2(void)
00684 {
00685   myConn.setPort(ArUtil::COM2);
00686   portToMovement();
00687 }
00688 
00689 AREXPORT void ArModeCamera::com3(void)
00690 {
00691   myConn.setPort(ArUtil::COM3);
00692   portToMovement();
00693 }
00694 
00695 AREXPORT void ArModeCamera::com4(void)
00696 {
00697   myConn.setPort(ArUtil::COM4);
00698   portToMovement();
00699 }
00700 
00701 AREXPORT void ArModeCamera::aux1(void)
00702 {
00703   myCam->setAuxPort(1);
00704   auxToMovement();
00705 }
00706 AREXPORT void ArModeCamera::aux2(void)
00707 {
00708   myCam->setAuxPort(2);
00709   auxToMovement();
00710 }
00711 
00712 void ArModeCamera::cameraToMovement(void)
00713 {
00714   myState = STATE_MOVEMENT;
00715   myCam->init();
00716   myRobot->setPTZ(myCam);
00717   giveUpCameraKeys();
00718   takeMovementKeys();
00719   helpMovementKeys();
00720 }
00721 
00722 void ArModeCamera::cameraToPort(void)
00723 {
00724   myState = STATE_PORT;
00725   giveUpCameraKeys();
00726   takePortKeys();
00727   helpPortKeys();
00728 }
00729 
00730 void ArModeCamera::cameraToAux(void)
00731 {
00732   giveUpCameraKeys();
00733   takeAuxKeys();
00734   helpAuxKeys();
00735 }
00736 
00737 void ArModeCamera::portToMovement(void)
00738 {
00739   if (!myConn.openSimple())
00740   {
00741     ArLog::log(ArLog::Terse, 
00742            "\n\nCould not open camera on that port, try another port.\n");
00743     helpPortKeys();
00744     return;
00745   }
00746   myCam->setDeviceConnection(&myConn);
00747   myCam->init();
00748   myRobot->setPTZ(myCam);
00749   myState = STATE_MOVEMENT;
00750   giveUpPortKeys();
00751   takeMovementKeys();
00752   helpMovementKeys();
00753 }
00754 
00755 void ArModeCamera::auxToMovement(void)
00756 {
00757   myCam->init();
00758   myRobot->setPTZ(myCam);
00759   myState = STATE_MOVEMENT;
00760   giveUpAuxKeys();
00761   takeMovementKeys();
00762   helpMovementKeys();
00763 }
00764 
00765 void ArModeCamera::takeCameraKeys(void)
00766 {
00767   addKeyHandler('1', &mySonyCB);
00768   addKeyHandler('2', &myCanonCB);
00769   addKeyHandler('3', &myDpptuCB);
00770   addKeyHandler('4', &myAmptuCB);
00771   addKeyHandler('5', &myCanonInvertedCB);
00772   addKeyHandler('!', &mySonySerialCB);
00773   addKeyHandler('@', &myCanonSerialCB);
00774   addKeyHandler('#', &myDpptuSerialCB);
00775   addKeyHandler('$', &myAmptuSerialCB);
00776   addKeyHandler('%', &myCanonInvertedSerialCB);
00777 }
00778 
00779 void ArModeCamera::giveUpCameraKeys(void)
00780 {
00781   remKeyHandler(&myCanonCB);
00782   remKeyHandler(&mySonyCB);
00783   remKeyHandler(&myDpptuCB);
00784   remKeyHandler(&myAmptuCB);
00785   remKeyHandler(&myCanonInvertedCB);
00786   remKeyHandler(&mySonySerialCB);
00787   remKeyHandler(&myCanonSerialCB);
00788   remKeyHandler(&myDpptuSerialCB);
00789   remKeyHandler(&myAmptuSerialCB);
00790   remKeyHandler(&myCanonInvertedSerialCB);
00791 }
00792 
00793 void ArModeCamera::helpCameraKeys(void)
00794 {
00795   ArLog::log(ArLog::Terse, 
00796          "You now need to select what type of camera you have.");
00797   ArLog::log(ArLog::Terse, 
00798          "%13s: select a SONY PTZ camera attached to the robot", "'1'");
00799   ArLog::log(ArLog::Terse, 
00800          "%13s: select a Canon VCC4 camera attached to the robot", "'2'");
00801   ArLog::log(ArLog::Terse, 
00802          "%13s: select a DPPTU camera attached to the robot", "'3'");
00803   ArLog::log(ArLog::Terse, 
00804          "%13s: select an AMPTU camera attached to the robot", "'4'");
00805   ArLog::log(ArLog::Terse, 
00806          "%13s: select an inverted Canon VCC4 camera attached to the robot", "'5'");
00807 
00808   ArLog::log(ArLog::Terse, 
00809          "%13s: select a SONY PTZ camera attached to a serial port", 
00810          "'!'");
00811   ArLog::log(ArLog::Terse, 
00812          "%13s: select a Canon VCC4 camera attached to a serial port", 
00813          "'@'");
00814   ArLog::log(ArLog::Terse, 
00815          "%13s: select a DPPTU camera attached to a serial port",
00816          "'#'");
00817   ArLog::log(ArLog::Terse, 
00818          "%13s: select an AMPTU camera attached to a serial port", 
00819          "'$'");
00820   ArLog::log(ArLog::Terse, 
00821          "%13s: select an inverted Canon VCC4 camera attached to a serial port", 
00822          "'%'");
00823 }
00824 
00825 void ArModeCamera::takePortKeys(void)
00826 {
00827   addKeyHandler('1', &myCom1CB);
00828   addKeyHandler('2', &myCom2CB);
00829   addKeyHandler('3', &myCom3CB);
00830   addKeyHandler('4', &myCom4CB);
00831 }
00832 
00833 void ArModeCamera::giveUpPortKeys(void)
00834 {
00835   remKeyHandler(&myCom1CB);
00836   remKeyHandler(&myCom2CB);
00837   remKeyHandler(&myCom3CB);
00838   remKeyHandler(&myCom4CB);
00839 }
00840 
00841 void ArModeCamera::helpPortKeys(void)
00842 {
00843   ArLog::log(ArLog::Terse, 
00844          "You now need to select what port your camera is on.");
00845   ArLog::log(ArLog::Terse, "%13s:  select COM1 or /dev/ttyS0", "'1'");
00846   ArLog::log(ArLog::Terse, "%13s:  select COM2 or /dev/ttyS1", "'2'");
00847   ArLog::log(ArLog::Terse, "%13s:  select COM3 or /dev/ttyS2", "'3'");
00848   ArLog::log(ArLog::Terse, "%13s:  select COM4 or /dev/ttyS3", "'4'");
00849 }
00850 
00851 void ArModeCamera::takeAuxKeys(void)
00852 {
00853   addKeyHandler('1', &myAux1CB);
00854   addKeyHandler('2', &myAux2CB);
00855 }
00856 
00857 void ArModeCamera::giveUpAuxKeys(void)
00858 {
00859   remKeyHandler(&myAux1CB);
00860   remKeyHandler(&myAux2CB);
00861 }
00862 
00863 void ArModeCamera::helpAuxKeys(void)
00864 {
00865   ArLog::log(ArLog::Terse,
00866              "You now need to select what aux port your camera is on.");
00867   ArLog::log(ArLog::Terse, "%13s:  select AUX1", "'1'");
00868   ArLog::log(ArLog::Terse, "%13s:  select AUX2", "'2'");
00869 }
00870 
00871 void ArModeCamera::takeMovementKeys(void)
00872 {
00873   addKeyHandler(ArKeyHandler::UP, &myUpCB);
00874   addKeyHandler(ArKeyHandler::DOWN, &myDownCB);
00875   addKeyHandler(ArKeyHandler::LEFT, &myLeftCB);
00876   addKeyHandler(ArKeyHandler::RIGHT, &myRightCB);
00877   addKeyHandler(ArKeyHandler::SPACE, &myCenterCB);
00878   addKeyHandler('e', &myExerciseCB);
00879   addKeyHandler('E', &myExerciseCB);
00880   if (myCam->canZoom())
00881   {
00882     addKeyHandler('z', &myZoomInCB);
00883     addKeyHandler('Z', &myZoomInCB);
00884     addKeyHandler('x', &myZoomOutCB);
00885     addKeyHandler('X', &myZoomOutCB);
00886   }
00887 }
00888 
00889 void ArModeCamera::giveUpMovementKeys(void)
00890 {
00891   remKeyHandler(&myUpCB);
00892   remKeyHandler(&myDownCB);
00893   remKeyHandler(&myLeftCB);
00894   remKeyHandler(&myRightCB);
00895   remKeyHandler(&myCenterCB);
00896   remKeyHandler(&myExerciseCB);
00897   if (myCam->canZoom())
00898   {
00899     remKeyHandler(&myZoomInCB);
00900     remKeyHandler(&myZoomOutCB);
00901   }
00902 }
00903 
00904 void ArModeCamera::helpMovementKeys(void)
00905 {
00906   ArLog::log(ArLog::Terse, 
00907          "Camera mode will now let you move the camera.");
00908   ArLog::log(ArLog::Terse, "%13s:  tilt camera up", "up arrow");
00909   ArLog::log(ArLog::Terse, "%13s:  tilt camera down", "down arrow");
00910   ArLog::log(ArLog::Terse, "%13s:  pan camera left", "left arrow");
00911   ArLog::log(ArLog::Terse, "%13s:  pan camera right", "right arrow");
00912   ArLog::log(ArLog::Terse, "%13s:  center camera and zoom out", 
00913          "space bar");
00914   ArLog::log(ArLog::Terse, "%13s:  exercise the camera", "'e' or 'E'");
00915   if (myCam->canZoom())
00916   {
00917     ArLog::log(ArLog::Terse, "%13s:  zoom in", "'z' or 'Z'");
00918     ArLog::log(ArLog::Terse, "%13s:  zoom out", "'x' or 'X'");
00919   }
00920 }
00921 
00922 AREXPORT ArModeSonar::ArModeSonar(ArRobot *robot, const char *name, char key,
00923                   char key2) :
00924   ArMode(robot, name, key, key2),
00925   myAllSonarCB(this, &ArModeSonar::allSonar),
00926   myFirstSonarCB(this, &ArModeSonar::firstSonar),
00927   mySecondSonarCB(this, &ArModeSonar::secondSonar),
00928   myThirdSonarCB(this, &ArModeSonar::thirdSonar),
00929   myFourthSonarCB(this, &ArModeSonar::fourthSonar)
00930 {
00931   myState = STATE_FIRST;
00932 }
00933 
00934 AREXPORT ArModeSonar::~ArModeSonar()
00935 {
00936 
00937 }
00938 
00939 AREXPORT void ArModeSonar::activate(void)
00940 {
00941   if (!baseActivate())
00942     return;
00943   addKeyHandler('1', &myAllSonarCB);
00944   addKeyHandler('2', &myFirstSonarCB);
00945   addKeyHandler('3', &mySecondSonarCB);
00946   addKeyHandler('4', &myThirdSonarCB);
00947   addKeyHandler('5', &myFourthSonarCB);
00948 }
00949 
00950 AREXPORT void ArModeSonar::deactivate(void)
00951 {
00952   if (!baseDeactivate())
00953     return;
00954   remKeyHandler(&myAllSonarCB);
00955   remKeyHandler(&myFirstSonarCB);
00956   remKeyHandler(&mySecondSonarCB);
00957   remKeyHandler(&myThirdSonarCB);
00958   remKeyHandler(&myFourthSonarCB);
00959 }
00960 
00961 AREXPORT void ArModeSonar::help(void)
00962 {
00963   int i;
00964   ArLog::log(ArLog::Terse, "This mode displays different segments of sonar.");
00965   ArLog::log(ArLog::Terse, 
00966          "You can use these keys to switch what is displayed:");
00967   ArLog::log(ArLog::Terse, "%13s: display all sonar", "'1'");
00968   ArLog::log(ArLog::Terse, "%13s: display sonar 0 - 7", "'2'");
00969   ArLog::log(ArLog::Terse, "%13s: display sonar 8 - 15", "'3'");
00970   ArLog::log(ArLog::Terse, "%13s: display sonar 16 - 23", "'4'");
00971   ArLog::log(ArLog::Terse, "%13s: display sonar 24 - 31", "'5'");
00972   ArLog::log(ArLog::Terse, "Sonar readings:");
00973   if (myState == STATE_ALL)
00974   {
00975     ArLog::log(ArLog::Terse, "Displaying all sonar.");
00976     for (i = 0; i < myRobot->getNumSonar(); ++i)
00977       printf("%6d", i); 
00978   }
00979   else if (myState == STATE_FIRST)
00980   {
00981     ArLog::log(ArLog::Terse, "Displaying 0-7 sonar.");
00982     for (i = 0; i < myRobot->getNumSonar() && i <= 7; ++i)
00983       printf("%6d", i); 
00984   }
00985   else if (myState == STATE_SECOND)
00986   {
00987     ArLog::log(ArLog::Terse, "Displaying 8-15 sonar.");
00988     for (i = 8; i < myRobot->getNumSonar() && i <= 15; ++i)
00989       printf("%6d", i); 
00990   }
00991   else if (myState == STATE_THIRD)
00992   {
00993     ArLog::log(ArLog::Terse, "Displaying 16-23 sonar.");
00994     for (i = 16; i < myRobot->getNumSonar() && i <= 23; ++i)
00995       printf("%6d", i); 
00996   }
00997   else if (myState == STATE_FOURTH)
00998   {
00999     ArLog::log(ArLog::Terse, "Displaying 24-31 sonar.");
01000     for (i = 24; i < myRobot->getNumSonar() && i <= 31; ++i)
01001       printf("%6d", i); 
01002   }
01003   printf("\n");
01004 }
01005 
01006 AREXPORT void ArModeSonar::userTask(void)
01007 {
01008   int i;
01009   printf("\r");
01010   if (myState == STATE_ALL)
01011   {
01012     for (i = 0; i < myRobot->getNumSonar(); ++i)
01013       printf("%6d", myRobot->getSonarRange(i)); 
01014   }
01015   else if (myState == STATE_FIRST)
01016   {
01017      for (i = 0; i < myRobot->getNumSonar() && i <= 7; ++i)
01018       printf("%6d", myRobot->getSonarRange(i));
01019   }
01020   else if (myState == STATE_SECOND)
01021   {
01022      for (i = 8; i < myRobot->getNumSonar() && i <= 15; ++i)
01023       printf("%6d", myRobot->getSonarRange(i));
01024   }
01025   else if (myState == STATE_THIRD)
01026   {
01027     for (i = 16; i < myRobot->getNumSonar() && i <= 23; ++i)
01028       printf("%6d", myRobot->getSonarRange(i)); 
01029   }
01030   else if (myState == STATE_FOURTH)
01031   {
01032     for (i = 24; i < myRobot->getNumSonar() && i <= 31; ++i)
01033       printf("%6d", myRobot->getSonarRange(i)); 
01034   }
01035 }
01036 
01037 AREXPORT void ArModeSonar::allSonar(void)
01038 {
01039   myState = STATE_ALL;
01040   printf("\n");
01041   help();
01042 }
01043 
01044 AREXPORT void ArModeSonar::firstSonar(void)
01045 {
01046   myState = STATE_FIRST;
01047   printf("\n");
01048   help();
01049 }
01050 
01051 AREXPORT void ArModeSonar::secondSonar(void)
01052 {
01053   myState = STATE_SECOND;
01054   printf("\n");
01055   help();
01056 }
01057 
01058 AREXPORT void ArModeSonar::thirdSonar(void)
01059 {
01060   myState = STATE_THIRD;
01061   printf("\n");
01062   help();
01063 }
01064 
01065 AREXPORT void ArModeSonar::fourthSonar(void)
01066 {
01067   myState = STATE_FOURTH;
01068   printf("\n");
01069   help();
01070 }
01071 
01072 AREXPORT ArModeBumps::ArModeBumps(ArRobot *robot, const char *name, char key, char key2): 
01073   ArMode(robot, name, key, key2)
01074 {
01075 }
01076 
01077 AREXPORT ArModeBumps::~ArModeBumps()
01078 {
01079   
01080 }
01081 
01082 AREXPORT void ArModeBumps::activate(void)
01083 {
01084   if (!baseActivate())
01085     return;
01086 }
01087 
01088 AREXPORT void ArModeBumps::deactivate(void)
01089 {
01090   if (!baseDeactivate())
01091     return;
01092 }
01093 
01094 AREXPORT void ArModeBumps::help(void)
01095 {
01096   unsigned int i;
01097   ArLog::log(ArLog::Terse, "Bumps mode will display whether bumpers are triggered or not...");
01098   ArLog::log(ArLog::Terse, "keep in mind it is assuming you have a full bump ring... so you should");
01099   ArLog::log(ArLog::Terse, "ignore readings for where there aren't bumpers.");
01100   ArLog::log(ArLog::Terse, "Bumper readings:");
01101   for (i = 0; i < myRobot->getNumFrontBumpers(); i++)
01102   {
01103     printf("%6d", i + 1);
01104   }
01105   printf(" |");
01106   for (i = 0; i < myRobot->getNumRearBumpers(); i++)
01107   {
01108     printf("%6d", i + 1);
01109   }
01110   printf("\n");
01111 }
01112 
01113 AREXPORT void ArModeBumps::userTask(void)
01114 {
01115   unsigned int i;
01116   int val;
01117   int bit;
01118   if (myRobot == NULL)
01119     return;
01120   printf("\r");
01121   val = ((myRobot->getStallValue() & 0xff00) >> 8);
01122   for (i = 0, bit = 2; i < myRobot->getNumFrontBumpers(); i++, bit *= 2)
01123   {
01124     if (val & bit)
01125       printf("%6s", "trig");
01126     else
01127       printf("%6s", "clear");
01128   }
01129   printf(" |");
01130   val = ((myRobot->getStallValue() & 0xff));
01131   for (i = 0, bit = 2; i < myRobot->getNumRearBumpers(); i++, bit *= 2)
01132   {
01133     if (val & bit)
01134       printf("%6s", "trig");
01135     else
01136       printf("%6s", "clear");
01137   }
01138 
01139 }
01140 
01141 AREXPORT ArModePosition::ArModePosition(ArRobot *robot, const char *name, char key, char key2, ArAnalogGyro *gyro): 
01142   ArMode(robot, name, key, key2),
01143   myUpCB(this, &ArModePosition::up),
01144   myDownCB(this, &ArModePosition::down),
01145   myLeftCB(this, &ArModePosition::left),
01146   myRightCB(this, &ArModePosition::right),
01147   myStopCB(this, &ArModePosition::stop),
01148   myResetCB(this, &ArModePosition::reset),
01149   myModeCB(this, &ArModePosition::mode),
01150   myGyroCB(this, &ArModePosition::gyro),
01151   myIncDistCB(this, &ArModePosition::incDistance),
01152   myDecDistCB(this, &ArModePosition::decDistance)
01153 {
01154   myGyro = gyro;
01155   myMode = MODE_BOTH;
01156   myModeString = "both";
01157   myInHeadingMode = false;
01158   myDistance = 1000;
01159 
01160   if (myGyro != NULL && !myGyro->hasNoInternalData())
01161     myGyroZero = myGyro->getHeading();
01162   myRobotZero = myRobot->getRawEncoderPose().getTh();
01163   myInHeadingMode = true;
01164   myHeading = myRobot->getTh();
01165 }
01166 
01167 AREXPORT ArModePosition::~ArModePosition()
01168 {
01169   
01170 }
01171 
01172 AREXPORT void ArModePosition::activate(void)
01173 {
01174   if (!baseActivate())
01175     return;
01176 
01177   addKeyHandler(ArKeyHandler::UP, &myUpCB);
01178   addKeyHandler(ArKeyHandler::DOWN, &myDownCB);
01179   addKeyHandler(ArKeyHandler::LEFT, &myLeftCB);  
01180   addKeyHandler(ArKeyHandler::RIGHT, &myRightCB);
01181   addKeyHandler(ArKeyHandler::SPACE, &myStopCB);
01182   addKeyHandler(ArKeyHandler::PAGEUP, &myIncDistCB);
01183   addKeyHandler(ArKeyHandler::PAGEDOWN, &myDecDistCB);
01184   addKeyHandler('r', &myResetCB);
01185   addKeyHandler('R', &myResetCB);
01186   addKeyHandler('x', &myModeCB);
01187   addKeyHandler('X', &myModeCB);
01188   addKeyHandler('z', &myGyroCB);
01189   addKeyHandler('Z', &myGyroCB);
01190 }
01191 
01192 AREXPORT void ArModePosition::deactivate(void)
01193 {
01194   if (!baseDeactivate())
01195     return;
01196 
01197   remKeyHandler(&myUpCB);
01198   remKeyHandler(&myDownCB);
01199   remKeyHandler(&myLeftCB);
01200   remKeyHandler(&myRightCB);
01201   remKeyHandler(&myStopCB);
01202   remKeyHandler(&myResetCB);
01203   remKeyHandler(&myModeCB);
01204   remKeyHandler(&myGyroCB);
01205   remKeyHandler(&myIncDistCB);
01206   remKeyHandler(&myDecDistCB);
01207 }
01208 
01209 AREXPORT void ArModePosition::up(void)
01210 {
01211   myRobot->move(myDistance);
01212   if (myInHeadingMode)
01213   {
01214     myInHeadingMode = false;
01215     myHeading = myRobot->getTh();
01216   }
01217 }
01218 
01219 AREXPORT void ArModePosition::down(void)
01220 {
01221   myRobot->move(-myDistance);
01222   if (myInHeadingMode)
01223   {
01224     myInHeadingMode = false;
01225     myHeading = myRobot->getTh();
01226   }
01227 }
01228 
01229 AREXPORT void ArModePosition::incDistance(void)
01230 {
01231   myDistance += 500;
01232 }
01233 
01234 AREXPORT void ArModePosition::decDistance(void)
01235 {
01236   myDistance -= 500;
01237   if(myDistance < 500) myDistance = 500;
01238 }
01239 
01240 AREXPORT void ArModePosition::left(void)
01241 {
01242   myRobot->setDeltaHeading(90);
01243   myInHeadingMode = true;
01244 }
01245 
01246 AREXPORT void ArModePosition::right(void)
01247 {
01248   myRobot->setDeltaHeading(-90);
01249   myInHeadingMode = true;
01250 }
01251 
01252 AREXPORT void ArModePosition::stop(void)
01253 {
01254   myRobot->stop();
01255   myInHeadingMode = true;
01256 }
01257 
01258 AREXPORT void ArModePosition::reset(void)
01259 {
01260   myRobot->stop();
01261   myRobot->moveTo(ArPose(0, 0, 0));
01262   if (myGyro != NULL && !myGyro->hasNoInternalData())
01263     myGyroZero = myGyro->getHeading();
01264   myRobotZero = myRobot->getRawEncoderPose().getTh();
01265   myInHeadingMode = true;
01266   myHeading = myRobot->getTh();
01267 }
01268 
01269 AREXPORT void ArModePosition::mode(void)
01270 {
01271   if (myMode == MODE_BOTH)
01272   {
01273     myMode = MODE_EITHER;
01274     myModeString = "either";
01275     myInHeadingMode = true;
01276     myRobot->stop();
01277   }
01278   else if (myMode == MODE_EITHER)
01279   {
01280     myMode = MODE_BOTH;
01281     myModeString = "both";
01282   }
01283 }
01284 
01285 AREXPORT void ArModePosition::gyro(void)
01286 {
01287   if (myGyro == NULL || !myGyro->haveGottenData())
01288     return;
01289 
01290   if (myGyro != NULL && myGyro->isActive())
01291     myGyro->deactivate();
01292   else if (myGyro != NULL && !myGyro->isActive() && 
01293        myGyro->hasGyroOnlyMode() && !myGyro->isGyroOnlyActive())
01294     myGyro->activateGyroOnly();
01295   else if (myGyro != NULL && !myGyro->isActive())
01296     myGyro->activate();
01297 
01298   help();
01299 }
01300 
01301 AREXPORT void ArModePosition::help(void)
01302 {
01303   ArLog::log(ArLog::Terse, "Mode is one of two values:");
01304   ArLog::log(ArLog::Terse, "%13s: heading and move can happen simultaneously", 
01305          "both");
01306   ArLog::log(ArLog::Terse, "%13s: only heading or move is active (move holds heading)", "either");
01307   ArLog::log(ArLog::Terse, "");
01308   ArLog::log(ArLog::Terse, "%13s:  forward %.1f meter(s)", "up arrow", myDistance/1000.0);
01309   ArLog::log(ArLog::Terse, "%13s:  backward %.1f meter(s)", "down arrow", myDistance/1000.0);
01310   ArLog::log(ArLog::Terse, "%13s:  increase distance by 1/2 meter", "page up");
01311   ArLog::log(ArLog::Terse, "%13s:  decrease distance by 1/2 meter", "page down");
01312   ArLog::log(ArLog::Terse, "%13s:  turn left 90 degrees", "left arrow");
01313   ArLog::log(ArLog::Terse, "%13s:  turn right 90 degrees", "right arrow");
01314   ArLog::log(ArLog::Terse, "%13s:  stop", "space bar");
01315   ArLog::log(ArLog::Terse, "%13s:  reset position to (0, 0, 0)", "'r' or 'R'");
01316   ArLog::log(ArLog::Terse, "%13s:  switch heading/velocity mode","'x' or 'X'");
01317   if (myGyro != NULL && myGyro->haveGottenData() && !myGyro->hasGyroOnlyMode())
01318     ArLog::log(ArLog::Terse, "%13s:  turn gyro on or off (stays this way in other modes)","'z' or 'Z'");
01319   if (myGyro != NULL && myGyro->haveGottenData() && myGyro->hasGyroOnlyMode())
01320     ArLog::log(ArLog::Terse, "%13s:  turn gyro on or off or gyro only (stays this way in other modes)","'z' or 'Z'");
01321 
01322   ArLog::log(ArLog::Terse, "");
01323   ArLog::log(ArLog::Terse, "Position mode shows the position stats on a robot.");
01324   if (myGyro != NULL && myGyro->haveGottenData() && 
01325       !myGyro->hasNoInternalData())
01326     ArLog::log(ArLog::Terse, "%7s%7s%9s%7s%8s%7s%8s%6s%10s%10s", "x", "y", "th", "comp", "volts", "mpacs", "mode", "gyro", "gyro_th", "robot_th");
01327   else if (myGyro != NULL && myGyro->haveGottenData() && 
01328        myGyro->hasNoInternalData())
01329     ArLog::log(ArLog::Terse, "%7s%7s%9s%7s%8s%7s%8s%6s", "x", "y", "th", "comp", "volts", "mpacs", "mode", "gyro");
01330   else
01331     ArLog::log(ArLog::Terse, "%7s%7s%9s%7s%8s%7s%8s", "x", "y", "th", "comp", "volts", "mpacs", "mode");
01332   
01333 }
01334 
01335 AREXPORT void ArModePosition::userTask(void)
01336 {
01337   if (myRobot == NULL)
01338     return;
01339   // if we're in either mode and not in the heading mode try to keep the
01340   // same heading (in heading mode its controlled by those commands)
01341   if (myMode == MODE_EITHER && !myInHeadingMode)
01342   {
01343     myRobot->setHeading(myHeading);
01344   }
01345   double voltage;
01346   if (myRobot->getRealBatteryVoltage() > 0)
01347     voltage = myRobot->getRealBatteryVoltage();
01348   else
01349     voltage = myRobot->getBatteryVoltage();
01350 
01351   std::string gyroString;
01352   if (myGyro == NULL)
01353     gyroString = "none";
01354   else if (myGyro->isActive())
01355     gyroString = "on";
01356   else if (myGyro->hasGyroOnlyMode() && myGyro->isGyroOnlyActive())
01357     gyroString = "only";
01358   else
01359     gyroString = "off";
01360 
01361   if (myGyro != NULL && myGyro->haveGottenData() && 
01362       !myGyro->hasNoInternalData())
01363     printf("\r%7.0f%7.0f%9.2f%7.0f%8.2f%7d%8s%6s%10.2f%10.2f", 
01364        myRobot->getX(),  myRobot->getY(), myRobot->getTh(), 
01365        myRobot->getCompass(), voltage,
01366        myRobot->getMotorPacCount(),
01367        myMode == MODE_BOTH ? "both" : "either", 
01368        gyroString.c_str(),
01369        ArMath::subAngle(myGyro->getHeading(), myGyroZero), 
01370        ArMath::subAngle(myRobot->getRawEncoderPose().getTh(),myRobotZero));
01371   else if (myGyro != NULL && myGyro->haveGottenData() && 
01372       myGyro->hasNoInternalData())
01373     printf("\r%7.0f%7.0f%9.2f%7.0f%8.2f%7d%8s%6s", 
01374        myRobot->getX(),  myRobot->getY(), myRobot->getTh(), 
01375        myRobot->getCompass(), voltage,
01376        myRobot->getMotorPacCount(),
01377        myMode == MODE_BOTH ? "both" : "either", 
01378        gyroString.c_str());
01379   else
01380     printf("\r%7.0f%7.0f%9.2f%7.0f%8.2f%7d%8s", myRobot->getX(), 
01381        myRobot->getY(), myRobot->getTh(), myRobot->getCompass(), 
01382        voltage, myRobot->getMotorPacCount(), 
01383        myMode == MODE_BOTH ? "both" : "either");
01384 }
01385 
01386 AREXPORT ArModeIO::ArModeIO(ArRobot *robot, const char *name, char key, char key2): 
01387   ArMode(robot, name, key, key2)
01388 {
01389 }
01390 
01391 AREXPORT ArModeIO::~ArModeIO()
01392 {
01393   
01394 }
01395 
01396 AREXPORT void ArModeIO::activate(void)
01397 {
01398   if (!baseActivate())
01399     return;
01400   if (myRobot == NULL)
01401     return;
01402   myRobot->comInt(ArCommands::IOREQUEST, 2);
01403   myOutput[0] = '\0';
01404   myLastPacketTime = myRobot->getIOPacketTime();
01405 }
01406 
01407 AREXPORT void ArModeIO::deactivate(void)
01408 {
01409   if (!baseDeactivate())
01410     return;
01411   if (myRobot == NULL)
01412     return;
01413   myRobot->comInt(ArCommands::IOREQUEST, 0);
01414 }
01415 
01416 AREXPORT void ArModeIO::help(void)
01417 {
01418   ArLog::log(ArLog::Terse, 
01419          "IO mode shows the IO (digin, digout, a/d) from the robot.");
01420   myExplanationReady = false;
01421   myExplained = false;
01422 }
01423 
01424 AREXPORT void ArModeIO::userTask(void)
01425 {
01426   int num;
01427   int i, j;
01428   unsigned int value;
01429   int bit;
01430   char label[256];
01431   myOutput[0] = '\0';
01432 
01433   if (myLastPacketTime.mSecSince(myRobot->getIOPacketTime()) == 0)
01434     return;
01435 
01436   if (!myExplanationReady)
01437     myExplanation[0] = '\0';
01438 
01439   value = myRobot->getFlags();
01440   if (!myExplanationReady)
01441   {
01442     sprintf(label, "flags");
01443     sprintf(myExplanation, "%s%17s  ", myExplanation, label);
01444   }
01445   for (j = 0, bit = 1; j < 16; ++j, bit *= 2)
01446   {
01447     if (j == 8)
01448       sprintf(myOutput, "%s ", myOutput);
01449     if (value & bit)
01450       sprintf(myOutput, "%s%d", myOutput, 1);
01451     else
01452       sprintf(myOutput, "%s%d", myOutput, 0);
01453   }
01454   sprintf(myOutput, "%s  ", myOutput);
01455 
01456   if (myRobot->hasFaultFlags())
01457   {
01458     value = myRobot->getFaultFlags();
01459     if (!myExplanationReady)
01460     {
01461       sprintf(label, "fault_flags");
01462       sprintf(myExplanation, "%s%17s  ", myExplanation, label);
01463     }
01464     for (j = 0, bit = 1; j < 16; ++j, bit *= 2)
01465     {
01466       if (j == 8)
01467     sprintf(myOutput, "%s ", myOutput);
01468       if (value & bit)
01469     sprintf(myOutput, "%s%d", myOutput, 1);
01470       else
01471     sprintf(myOutput, "%s%d", myOutput, 0);
01472     }
01473     sprintf(myOutput, "%s  ", myOutput);
01474   }
01475 
01476   num = myRobot->getIODigInSize();
01477   for (i = 0; i < num; ++i)
01478   {
01479     value = myRobot->getIODigIn(i);
01480     if (!myExplanationReady)
01481     {
01482       sprintf(label, "digin%d", i);
01483       sprintf(myExplanation, "%s%8s  ", myExplanation, label);
01484     }
01485     for (j = 0, bit = 1; j < 8; ++j, bit *= 2)
01486     {
01487       if (value & bit)
01488         sprintf(myOutput, "%s%d", myOutput, 1);
01489       else
01490         sprintf(myOutput, "%s%d", myOutput, 0);
01491     }
01492     sprintf(myOutput, "%s  ", myOutput);
01493   }
01494 
01495   num = myRobot->getIODigOutSize();
01496   for (i = 0; i < num; ++i)
01497   {
01498     value = myRobot->getIODigOut(i);
01499     if (!myExplanationReady)
01500     {
01501       sprintf(label, "digout%d", i);
01502       sprintf(myExplanation, "%s%8s  ", myExplanation, label);
01503     }
01504     for (j = 0, bit = 1; j < 8; ++j, bit *= 2)
01505     {
01506       if (value & bit)
01507         sprintf(myOutput, "%s%d", myOutput, 1);
01508       else
01509         sprintf(myOutput, "%s%d", myOutput, 0);
01510     }
01511     sprintf(myOutput, "%s  ", myOutput);
01512   }
01513 
01514   num = myRobot->getIOAnalogSize();
01515   for (i = 0; i < num; ++i)
01516   {
01517     if (!myExplanationReady)
01518     {
01519       sprintf(label, "a/d%d", i);
01520       sprintf(myExplanation, "%s%6s", myExplanation, label);
01521     }
01522     
01523     /*
01524       int ad = myRobot->getIOAnalog(i);
01525       double adVal;
01526     ad &= 0xfff;
01527     adVal = ad * .0048828;
01528     sprintf(myOutput, "%s%6.2f", myOutput,adVal);
01529     */
01530     sprintf(myOutput, "%s%6.2f", myOutput, myRobot->getIOAnalogVoltage(i));
01531     
01532   }
01533 
01534   if (!myExplained)
01535   {
01536     printf("\n%s\n", myExplanation);
01537     myExplained = true;
01538   }
01539 
01540   printf("\r%s", myOutput);
01541 }
01542 
01543 AREXPORT ArModeLaser::ArModeLaser(ArRobot *robot, const char *name, 
01544                   char key, char key2, ArSick *sick) :
01545   ArMode(robot, name, key, key2),
01546   myFailedConnectCB(this, &ArModeLaser::failedConnect),
01547   myTogMiddleCB(this, &ArModeLaser::togMiddle)
01548 {
01549   myState = STATE_UNINITED;
01550   mySick = sick;
01551   myConnectingLaser = false;
01552   myInitializedLaser = false;
01553   myPrintMiddle = false;
01554 }
01555 
01556 AREXPORT ArModeLaser::~ArModeLaser()
01557 {
01558 }
01559 
01560 AREXPORT void ArModeLaser::activate(void)
01561 {
01562   if (!baseActivate())
01563     return;
01564 
01565   addKeyHandler('z', &myTogMiddleCB);
01566   addKeyHandler('Z', &myTogMiddleCB);
01567   if (myRobot == NULL || mySick == NULL)
01568   {
01569     ArLog::log(ArLog::Terse, "Laser mode activated but either no robot or laser given to it.");
01570     return;
01571   }
01572   if (myState == STATE_UNINITED)
01573   {
01574     mySick->lockDevice();
01575     if (mySick->isConnected())
01576     {
01577       ArLog::log(ArLog::Verbose, 
01578          "\nArModeLaser using already existing and connected laser.");
01579       myState = STATE_CONNECTED;
01580     }
01581     else if (myConnectingLaser && !mySick->tryingToConnect())
01582     {
01583       ArLog::log(ArLog::Terse, 
01584          "\nArModeLaser trying to connect to a laser its already started once.");
01585       mySick->asyncConnect();
01586       myState = STATE_CONNECTING;
01587     } 
01588     else if (myConnectingLaser)
01589     {
01590       ArLog::log(ArLog::Terse, "\nArModeLaser already connecting to laser.");
01591     }
01592     else
01593     {
01594       ArLog::log(ArLog::Terse,
01595          "\nArModeLaser is connecting to the laser.");
01596       myConnectingLaser = true;
01597       myInitializedLaser = true;
01598       myRobot->remRangeDevice(mySick);
01599       myRobot->addRangeDevice(mySick);
01600       mySick->remFailedConnectCB(&myFailedConnectCB);
01601       mySick->addFailedConnectCB(&myFailedConnectCB, ArListPos::LAST);
01602       // run the laser in its own thread if it isn't already
01603       if (!mySick->getRunning())
01604     mySick->runAsync();
01605       // connect the thing
01606       if (!mySick->tryingToConnect())
01607     mySick->asyncConnect();
01608       myState = STATE_CONNECTING;
01609     }
01610     mySick->unlockDevice();
01611   } 
01612 }
01613 
01614 AREXPORT void ArModeLaser::deactivate(void)
01615 {
01616   if (!baseDeactivate())
01617     return;
01618 
01619   remKeyHandler(&myTogMiddleCB);
01620 }
01621 
01622 AREXPORT void ArModeLaser::help(void)
01623 {
01624   ArLog::log(ArLog::Terse, 
01625          "Laser mode connects to a laser, or uses a previously established connection.");
01626   ArLog::log(ArLog::Terse,
01627          "Laser mode then displays the closest and furthest reading from the laser.");
01628   ArLog::log(ArLog::Terse, "%13s:  toggle between far reading and middle reading with reflectivity", "'z' or 'Z'");
01629 
01630 }
01631 
01632 
01633 AREXPORT void ArModeLaser::userTask(void)
01634 {
01635   double dist, angle;
01636   int reflec;
01637   double midDist, midAngle;
01638   int midReflec;
01639   double farDist, farAngle;
01640 
01641   if (myRobot == NULL || mySick == NULL)
01642     return;
01643   if (myState == STATE_CONNECTED && !myPrintMiddle)
01644   {
01645     const std::list<ArPoseWithTime *> *readings;
01646     std::list<ArPoseWithTime *>::const_iterator it;
01647     bool found = false;
01648   
01649     mySick->lockDevice();
01650     if (!mySick->isConnected())
01651     {
01652       ArLog::log(ArLog::Terse, "\n\nLaser mode lost connection to the laser.");
01653       ArLog::log(ArLog::Terse, "Switch out of this mode and back if you want to try reconnecting to the laser.\n");
01654       myState = STATE_UNINITED;
01655     }
01656     dist = mySick->currentReadingPolar(-90, 90, &angle);
01657     if (dist < mySick->getMaxRange())
01658       printf("\rClose: %8.0fmm %5.1f deg   ", dist, angle);
01659     else
01660       printf("\rNo close reading.         ");
01661 
01662     readings = mySick->getCurrentBuffer();
01663     for (it = readings->begin(), found = false; it != readings->end(); it++)
01664     {
01665       dist = myRobot->findDistanceTo(*(*it));
01666       angle = myRobot->findDeltaHeadingTo(*(*it));
01667       if (!found || dist > farDist)
01668       {
01669     found = true;
01670     farDist = dist;
01671     farAngle = angle;
01672       }
01673     }
01674     if (found)
01675       printf("Far: %8.0fmm %5.1f deg", 
01676          farDist, farAngle);
01677     else
01678       printf("No far reading found");
01679     printf("         %d readings   ", readings->size());
01680     mySick->unlockDevice();
01681   }
01682   else if (myState == STATE_CONNECTED && myPrintMiddle)
01683   {
01684     const std::list<ArSensorReading *> *rawReadings;
01685     std::list<ArSensorReading *>::const_iterator rawIt;
01686     mySick->lockDevice();
01687     if (!mySick->isConnected())
01688     {
01689       ArLog::log(ArLog::Terse, "\n\nLaser mode lost connection to the laser.");
01690       ArLog::log(ArLog::Terse, "Switch out of this mode and back if you want to try reconnecting to the laser.\n");
01691       myState = STATE_UNINITED;
01692     }
01693     rawReadings = mySick->getRawReadings();
01694     int middleReading = rawReadings->size() / 2;
01695     if (rawReadings->begin() != rawReadings->end())
01696     {
01697       int i;
01698       for (rawIt = rawReadings->begin(), i = 0; 
01699        rawIt != rawReadings->end(); 
01700        rawIt++, i++)
01701       {
01702     if (rawIt == rawReadings->begin() || 
01703         (*rawIt)->getRange() < dist)
01704     {
01705       dist = (*rawIt)->getRange();
01706       angle = (*rawIt)->getSensorTh();
01707       reflec = (*rawIt)->getExtraInt();
01708     }
01709     if (i == middleReading)
01710     {
01711       midDist = (*rawIt)->getRange();
01712       midAngle = (*rawIt)->getSensorTh();
01713       midReflec = (*rawIt)->getExtraInt();
01714     }
01715       }
01716       printf(
01717       "\rClose: %8.0fmm %5.1f deg %d refl          Middle: %8.0fmm %5.1fdeg, %d refl", 
01718           dist, angle, reflec, midDist, midAngle, midReflec);
01719     }
01720     else
01721       printf("\rNo readings");
01722     mySick->unlockDevice(); 
01723   }
01724   else if (myState == STATE_CONNECTING)
01725   {
01726     mySick->lockDevice();
01727     if (mySick->isConnected())
01728     {
01729       ArLog::log(ArLog::Terse, "\nLaser mode has connected to the laser.\n");
01730       myState = STATE_CONNECTED;
01731     }
01732     mySick->unlockDevice();
01733   }
01734 }
01735 
01736 AREXPORT void ArModeLaser::failedConnect(void)
01737 {
01738   ArLog::log(ArLog::Terse, "\nLaser mode failed to connect to the laser.\n");
01739   ArLog::log(ArLog::Terse, 
01740          "Switch out of this mode and back to try reconnecting.\n");
01741   myState = STATE_UNINITED;
01742 }
01743 
01744 
01745 void ArModeLaser::togMiddle(void)
01746 {
01747   myPrintMiddle = !myPrintMiddle;
01748 }
01749 
01750 
01755 AREXPORT ArModeActs::ArModeActs(ArRobot *robot, const char *name, char key, 
01756                 char key2, ArACTS_1_2 *acts): 
01757   ArMode(robot, name, key, key2),
01758   myChannel1CB(this, &ArModeActs::channel1),
01759   myChannel2CB(this, &ArModeActs::channel2),
01760   myChannel3CB(this, &ArModeActs::channel3),
01761   myChannel4CB(this, &ArModeActs::channel4),
01762   myChannel5CB(this, &ArModeActs::channel5),
01763   myChannel6CB(this, &ArModeActs::channel6),
01764   myChannel7CB(this, &ArModeActs::channel7),
01765   myChannel8CB(this, &ArModeActs::channel8),
01766   myStopCB(this, &ArModeActs::stop),
01767   myStartCB(this, &ArModeActs::start),
01768   myToggleAcquireCB(this, &ArModeActs::toggleAcquire)
01769 {
01770   if (acts != NULL)
01771     myActs = acts;
01772   else
01773     myActs = new ArACTS_1_2;
01774   myRobot = robot;
01775   myActs->openPort(myRobot);
01776   myGroup = new ArActionGroupColorFollow(myRobot, myActs, camera);
01777   myGroup->deactivate();
01778 }
01779 
01780 // Destructor
01781 AREXPORT ArModeActs::~ArModeActs()
01782 {
01783   
01784 }
01785 
01786 // Activate the mode
01787 AREXPORT void ArModeActs::activate(void)
01788 {
01789   // Activate the group
01790   if (!baseActivate())
01791     return;
01792   myGroup->activateExclusive();
01793   
01794   // Add key handlers for keyboard input
01795   addKeyHandler(ArKeyHandler::SPACE, &myStopCB);
01796   addKeyHandler('z', &myStartCB);
01797   addKeyHandler('Z', &myStartCB);
01798   addKeyHandler('x', &myToggleAcquireCB);
01799   addKeyHandler('X', &myToggleAcquireCB);
01800   addKeyHandler('1', &myChannel1CB);
01801   addKeyHandler('2', &myChannel2CB);
01802   addKeyHandler('3', &myChannel3CB);
01803   addKeyHandler('4', &myChannel4CB);
01804   addKeyHandler('5', &myChannel5CB);
01805   addKeyHandler('6', &myChannel6CB);
01806   addKeyHandler('7', &myChannel7CB);
01807   addKeyHandler('8', &myChannel8CB);
01808 
01809   // Set the camera
01810   camera = myRobot->getPTZ();
01811   
01812   // Tell us whether we are connected to ACTS or not
01813   if(myActs->isConnected())
01814     { 
01815       printf("\nConnected to ACTS.\n");
01816     }
01817   else printf("\nNot connected to ACTS.\n");
01818 
01819   // Tell us whether a camera is defined or not
01820   if(camera != NULL)
01821     {
01822       printf("\nCamera defined.\n\n");
01823       myGroup->setCamera(camera);
01824     }
01825   else
01826     {  
01827       printf("\nNo camera defined.\n");
01828       printf("The robot will not tilt its camera up or down until\n");
01829       printf("a camera has been defined in camera mode ('c' or 'C').\n\n");
01830     }
01831 }
01832 
01833 // Deactivate the group
01834 AREXPORT void ArModeActs::deactivate(void)
01835 {
01836   if (!baseDeactivate())
01837     return;
01838 
01839   // Remove the key handlers
01840   remKeyHandler(&myStopCB);
01841   remKeyHandler(&myStartCB);
01842   remKeyHandler(&myToggleAcquireCB);
01843   remKeyHandler(&myChannel1CB);
01844   remKeyHandler(&myChannel2CB);
01845   remKeyHandler(&myChannel3CB);
01846   remKeyHandler(&myChannel4CB);
01847   remKeyHandler(&myChannel5CB);
01848   remKeyHandler(&myChannel6CB);
01849   remKeyHandler(&myChannel7CB);
01850   remKeyHandler(&myChannel8CB);
01851 
01852   myGroup->deactivate();
01853 }
01854 
01855 // Display the available commands
01856 AREXPORT void ArModeActs::help(void)
01857 {
01858   ArLog::log(ArLog::Terse, 
01859        "ACTS mode will drive the robot in an attempt to follow a color blob.\n");
01860 
01861   ArLog::log(ArLog::Terse, "%20s:  Pick a channel",     "1 - 8    ");
01862   ArLog::log(ArLog::Terse, "%20s:  toggle acquire mode", "'x' or 'X'");
01863   ArLog::log(ArLog::Terse, "%20s:  start movement",     "'z' or 'Z'");
01864   ArLog::log(ArLog::Terse, "%20s:  stop movement",      "space bar");
01865   ArLog::log(ArLog::Terse, "");
01866   
01867 }
01868 
01869 // Display data about this mode
01870 AREXPORT void ArModeActs::userTask(void)
01871 {
01872   int myChannel;
01873 
01874   char *acquire;
01875   char *move;
01876   char *blob;
01877 
01878   myChannel = myGroup->getChannel();
01879   if(myGroup->getAcquire()) acquire = "actively acquiring";
01880   else acquire = "passively acquiring";
01881   
01882   if(myGroup->getMovement()) move = "movement on";
01883   else move = "movement off";
01884 
01885   if(myGroup->getBlob()) blob = "blob in sight";
01886   else blob = "no blob in sight";
01887 
01888   printf("\r Channel: %d  %15s %25s %20s", myChannel, move, acquire, blob);
01889 }
01890 
01891 // The channels
01892 AREXPORT void ArModeActs::channel1(void)
01893 {
01894   myGroup->setChannel(1);
01895 }
01896 
01897 AREXPORT void ArModeActs::channel2(void)
01898 {
01899   myGroup->setChannel(2);
01900 }
01901 
01902 AREXPORT void ArModeActs::channel3(void)
01903 {
01904   myGroup->setChannel(3);
01905 }
01906 
01907 AREXPORT void ArModeActs::channel4(void)
01908 {
01909   myGroup->setChannel(4);
01910 }
01911 
01912 AREXPORT void ArModeActs::channel5(void)
01913 {
01914   myGroup->setChannel(5);
01915 }
01916 
01917 AREXPORT void ArModeActs::channel6(void)
01918 {
01919   myGroup->setChannel(6);
01920 }
01921 
01922 AREXPORT void ArModeActs::channel7(void)
01923 {
01924   myGroup->setChannel(7);
01925 }
01926 
01927 AREXPORT void ArModeActs::channel8(void)
01928 {
01929   myGroup->setChannel(8);
01930 }
01931 
01932 // Stop the robot from moving
01933 AREXPORT void ArModeActs::stop(void)
01934 {
01935   myGroup->stopMovement();
01936 }
01937 
01938 // Allow the robot to move
01939 AREXPORT void ArModeActs::start(void)
01940 {
01941   myGroup->startMovement();
01942 }
01943 
01944 // Toggle whether or not the robot is allowed
01945 // to aquire anything
01946 AREXPORT void ArModeActs::toggleAcquire()
01947 {
01948   if(myGroup->getAcquire())
01949     myGroup->setAcquire(false);
01950   else myGroup->setAcquire(true);
01951 
01952 }
01953 
01954 AREXPORT ArModeCommand::ArModeCommand(ArRobot *robot, const char *name, char key, char key2): 
01955   ArMode(robot, name, key, key2),
01956   my0CB(this, &ArModeCommand::addChar, '0'),
01957   my1CB(this, &ArModeCommand::addChar, '1'),
01958   my2CB(this, &ArModeCommand::addChar, '2'),
01959   my3CB(this, &ArModeCommand::addChar, '3'),
01960   my4CB(this, &ArModeCommand::addChar, '4'),
01961   my5CB(this, &ArModeCommand::addChar, '5'),
01962   my6CB(this, &ArModeCommand::addChar, '6'),
01963   my7CB(this, &ArModeCommand::addChar, '7'),
01964   my8CB(this, &ArModeCommand::addChar, '8'),
01965   my9CB(this, &ArModeCommand::addChar, '9'),
01966   myMinusCB(this, &ArModeCommand::addChar, '-'),
01967   myBackspaceCB(this, &ArModeCommand::addChar, ArKeyHandler::BACKSPACE),
01968   mySpaceCB(this, &ArModeCommand::addChar, ArKeyHandler::SPACE),
01969   myEnterCB(this, &ArModeCommand::finishParsing)
01970 
01971 {
01972   reset(false);
01973 }
01974 
01975 AREXPORT ArModeCommand::~ArModeCommand()
01976 {
01977   
01978 }
01979 
01980 AREXPORT void ArModeCommand::activate(void)
01981 {
01982   reset(false);
01983   if (!baseActivate())
01984     return;
01985   myRobot->stopStateReflection();
01986   takeKeys();
01987   reset(true);
01988 }
01989 
01990 AREXPORT void ArModeCommand::deactivate(void)
01991 {
01992   if (!baseDeactivate())
01993     return;
01994   giveUpKeys();
01995 }
01996 
01997 AREXPORT void ArModeCommand::help(void)
01998 {
01999   
02000   ArLog::log(ArLog::Terse, "Command mode has three ways to send commands");
02001   ArLog::log(ArLog::Terse, "%-30s: Sends com(<command>)", "<command>");
02002   ArLog::log(ArLog::Terse, "%-30s: Sends comInt(<command>, <integer>)", "<command> <integer>");
02003   ArLog::log(ArLog::Terse, "%-30s: Sends com2Bytes(<command>, <byte1>, <byte2>)", "<command> <byte1> <byte2>");
02004 }
02005 
02006 void ArModeCommand::addChar(int ch)
02007 {
02008   if (ch < '0' && ch > '9' && ch != '-' && ch != ArKeyHandler::BACKSPACE && 
02009       ch != ArKeyHandler::SPACE)
02010   {
02011     ArLog::log(ArLog::Terse, "Something horribly wrong in command mode since number is < 0 || > 9 (it is the value %d)", ch);
02012     return;
02013   }
02014 
02015   size_t size = sizeof(myCommandString);
02016   size_t len = strlen(myCommandString);
02017 
02018   if (ch == ArKeyHandler::BACKSPACE)
02019   {
02020     // don't overrun backwards
02021     if (len < 1)
02022       return;
02023     myCommandString[len-1] = '\0';
02024     printf("\r> %s  \r> %s", myCommandString, myCommandString);
02025     return;
02026   }
02027   if (ch == ArKeyHandler::SPACE)
02028   {
02029     // if we're at the start or have a space or - just return
02030     if (len < 1 || myCommandString[len-1] == ' ' || 
02031     myCommandString[len-1] == '-')
02032       return;
02033     myCommandString[len] = ' ';
02034     myCommandString[len+1] = '\0';
02035     printf(" ");
02036     return;
02037   }
02038   if (ch == '-')
02039   {
02040     // make sure it isn't the command trying to be negated or that its the start of the byte
02041     if (len < 1 || myCommandString[len-1] != ' ')
02042       return;
02043     printf("%c", '-');
02044     myCommandString[len] = '-';
02045     myCommandString[len+1] = '\0';
02046     return;
02047   }
02048   if (len + 1 >= size)
02049   {
02050     printf("\n");
02051     ArLog::log(ArLog::Terse, "Command is too long, abandoning command");
02052     reset();
02053     return;
02054   }
02055   else
02056   {
02057     printf("%c", ch);
02058     myCommandString[len] = ch;
02059     myCommandString[len+1] = '\0';
02060     return;
02061   }
02062 }
02063 
02064 void ArModeCommand::finishParsing(void)
02065 {
02066   
02067   ArArgumentBuilder builder;
02068   builder.add(myCommandString);
02069   int command;
02070   int int1;
02071   int int2;
02072 
02073   if (myCommandString[0] == '\0')
02074     return;
02075 
02076   printf("\n");
02077   if (builder.getArgc() == 0)
02078   {
02079     ArLog::log(ArLog::Terse, "Syntax error, no arguments.");
02080   }
02081   if (builder.getArgc() == 1)
02082   {
02083     command = builder.getArgInt(0);
02084     if (command < 0 || command > 255 || !builder.isArgInt(0))
02085     {
02086       ArLog::log(ArLog::Terse, 
02087          "Invalid command, must be an integer between 0 and 255");
02088       reset();
02089       return;
02090     }
02091     else
02092     {
02093       ArLog::log(ArLog::Terse, "com(%d)", command);
02094       myRobot->com(command);
02095       reset();
02096       return;
02097     }
02098   }
02099   else if (builder.getArgc() == 2)
02100   {
02101     command = builder.getArgInt(0);
02102     int1 = builder.getArgInt(1);
02103     if (command < 0 || command > 255 || !builder.isArgInt(0))
02104     {
02105       ArLog::log(ArLog::Terse, 
02106          "Invalid command, must be an integer between 0 and 255");
02107       reset();
02108       return;
02109     }
02110     else if (int1 < -32767 || int1 > 32767 || !builder.isArgInt(1))
02111     {
02112       ArLog::log(ArLog::Terse, 
02113      "Invalid integer, must be an integer between -32767 and 32767");
02114       reset();
02115       return;
02116     }
02117     else
02118     {
02119       ArLog::log(ArLog::Terse, "comInt(%d, %d)", command,
02120          int1);
02121       myRobot->comInt(command, int1);
02122       reset();
02123       return;
02124     }
02125   }
02126   else if (builder.getArgc() == 3)
02127   {
02128     command = builder.getArgInt(0);
02129     int1 = builder.getArgInt(1);
02130     int2 = builder.getArgInt(2);
02131     if (command < 0 || command > 255 || !builder.isArgInt(0))
02132     {
02133       ArLog::log(ArLog::Terse, 
02134          "Invalid command, must be between 0 and 255");
02135       reset();
02136       return;
02137     }
02138     else if (int1 < -128 || int1 > 255 || !builder.isArgInt(1))
02139     {
02140       ArLog::log(ArLog::Terse, 
02141      "Invalid byte1, must be an integer between -128 and 127, or between 0 and 255");
02142       reset();
02143       return;
02144     }
02145     else if (int2 < -128 || int2 > 255 || !builder.isArgInt(2))
02146     {
02147       ArLog::log(ArLog::Terse, 
02148      "Invalid byte2, must be an integer between -128 and 127, or between 0 and 255");
02149       reset();
02150       return;
02151     }
02152     else
02153     {
02154       ArLog::log(ArLog::Terse, 
02155          "com2Bytes(%d, %d, %d)", 
02156          command, int1, int2);
02157       myRobot->com2Bytes(command, int1, int2);
02158       reset();
02159       return;
02160     }
02161   }
02162   else
02163   {
02164     ArLog::log(ArLog::Terse, "Syntax error, too many arguments");
02165     reset();
02166     return;
02167   }
02168 }
02169 
02170 void ArModeCommand::reset(bool print)
02171 {
02172   myCommandString[0] = '\0';
02173   if (print)
02174   {
02175     ArLog::log(ArLog::Terse, "");
02176     printf("> ");
02177   }
02178 }
02179 
02180 void ArModeCommand::takeKeys(void)
02181 {
02182   addKeyHandler('0', &my0CB);
02183   addKeyHandler('1', &my1CB);
02184   addKeyHandler('2', &my2CB);
02185   addKeyHandler('3', &my3CB);
02186   addKeyHandler('4', &my4CB);
02187   addKeyHandler('5', &my5CB);
02188   addKeyHandler('6', &my6CB);
02189   addKeyHandler('7', &my7CB);
02190   addKeyHandler('8', &my8CB);
02191   addKeyHandler('9', &my9CB);
02192   addKeyHandler('-', &myMinusCB);
02193   addKeyHandler(ArKeyHandler::BACKSPACE, &myBackspaceCB);
02194   addKeyHandler(ArKeyHandler::ENTER, &myEnterCB);
02195   addKeyHandler(ArKeyHandler::SPACE, &mySpaceCB);
02196 }
02197 
02198 void ArModeCommand::giveUpKeys(void)
02199 {
02200   remKeyHandler(&my0CB);
02201   remKeyHandler(&my1CB);
02202   remKeyHandler(&my2CB);
02203   remKeyHandler(&my3CB);
02204   remKeyHandler(&my4CB);
02205   remKeyHandler(&my5CB);
02206   remKeyHandler(&my6CB);
02207   remKeyHandler(&my7CB);
02208   remKeyHandler(&my8CB);
02209   remKeyHandler(&my9CB);
02210   remKeyHandler(&myBackspaceCB);
02211   remKeyHandler(&myMinusCB);
02212   remKeyHandler(&myEnterCB);
02213   remKeyHandler(&mySpaceCB);
02214 }
02215 
02221 AREXPORT ArModeTCM2::ArModeTCM2(ArRobot *robot, const char *name, char key, char key2, ArTCM2 *tcm2): 
02222   ArMode(robot, name, key, key2)
02223 {
02224   if (tcm2 != NULL)
02225     myTCM2 = tcm2;
02226   else
02227     myTCM2 = new ArTCM2(robot);
02228   myOffCB = new ArFunctorC<ArTCM2>(myTCM2, &ArTCM2::commandOff);
02229   myCompassCB = new ArFunctorC<ArTCM2>(myTCM2, &ArTCM2::commandJustCompass);
02230   myOnePacketCB = new ArFunctorC<ArTCM2>(myTCM2, &ArTCM2::commandOnePacket);
02231   myContinuousPacketsCB = new ArFunctorC<ArTCM2>(
02232       myTCM2, &ArTCM2::commandContinuousPackets);
02233   myUserCalibrationCB = new ArFunctorC<ArTCM2>(
02234       myTCM2, &ArTCM2::commandUserCalibration);
02235   myAutoCalibrationCB = new ArFunctorC<ArTCM2>(
02236       myTCM2, &ArTCM2::commandAutoCalibration);
02237   myStopCalibrationCB = new ArFunctorC<ArTCM2>(
02238       myTCM2, &ArTCM2::commandStopCalibration);
02239   myResetCB = new ArFunctorC<ArTCM2>(
02240       myTCM2, &ArTCM2::commandSoftReset);
02241 
02242 }
02243 
02244 AREXPORT ArModeTCM2::~ArModeTCM2()
02245 {
02246   
02247 }
02248 
02249 AREXPORT void ArModeTCM2::activate(void)
02250 {
02251   if (!baseActivate())
02252     return;
02253   myTCM2->commandContinuousPackets();
02254   addKeyHandler('0', myOffCB);
02255   addKeyHandler('1', myCompassCB);
02256   addKeyHandler('2', myOnePacketCB);
02257   addKeyHandler('3', myContinuousPacketsCB);
02258   addKeyHandler('4', myUserCalibrationCB);
02259   addKeyHandler('5', myAutoCalibrationCB);
02260   addKeyHandler('6', myStopCalibrationCB);
02261   addKeyHandler('7', myResetCB);
02262 }
02263 
02264 AREXPORT void ArModeTCM2::deactivate(void)
02265 {
02266   if (!baseDeactivate())
02267     return;
02268   myTCM2->commandJustCompass();
02269   remKeyHandler(myOffCB);
02270   remKeyHandler(myCompassCB);
02271   remKeyHandler(myOnePacketCB);
02272   remKeyHandler(myContinuousPacketsCB);
02273   remKeyHandler(myUserCalibrationCB);
02274   remKeyHandler(myAutoCalibrationCB);
02275   remKeyHandler(myStopCalibrationCB);
02276   remKeyHandler(myResetCB);
02277 }
02278 
02279 AREXPORT void ArModeTCM2::help(void)
02280 {
02281   ArLog::log(ArLog::Terse, 
02282          "TCM2 mode shows the data from the TCM2 compass and lets you send the TCM2 commands");
02283   ArLog::log(ArLog::Terse, "%20s:  turn TCM2 off", "'0'");  
02284   ArLog::log(ArLog::Terse, "%20s:  just get compass readings", "'1'");  
02285   ArLog::log(ArLog::Terse, "%20s:  get a single set of TCM2 data", "'2'");  
02286   ArLog::log(ArLog::Terse, "%20s:  get continuous TCM2 data", "'3'");  
02287   ArLog::log(ArLog::Terse, "%20s:  start user calibration", "'4'");  
02288   ArLog::log(ArLog::Terse, "%20s:  start auto calibration", "'5'");  
02289   ArLog::log(ArLog::Terse, "%20s:  stop calibration and get a single set of data", "'6'");  
02290   ArLog::log(ArLog::Terse, "%20s:  soft reset of compass", "'7'");  
02291 
02292   printf("%6s %5s %5s %6s %6s %6s %6s %10s %4s %4s %6s %3s\n", 
02293      "comp", "pitch", "roll", "magX", "magY", "magZ", "temp", "error",
02294      "calH", "calV", "calM", "cnt");
02295 }
02296 
02297 AREXPORT void ArModeTCM2::userTask(void)
02298 {
02299   printf("\r%6.1f %5.1f %5.1f %6.2f %6.2f %6.2f %6.1f 0x%08x %4.0f %4.0f %6.2f %3d", 
02300      myTCM2->getCompass(), myTCM2->getPitch(), myTCM2->getRoll(), 
02301      myTCM2->getXMagnetic(), myTCM2->getYMagnetic(), 
02302      myTCM2->getZMagnetic(), 
02303      myTCM2->getTemperature(), myTCM2->getError(), 
02304      myTCM2->getCalibrationH(), myTCM2->getCalibrationV(), 
02305      myTCM2->getCalibrationM(), myTCM2->getPacCount());
02306 
02307 }

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