Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

ArmController.cc

Go to the documentation of this file.
00001 #include "Shared/RobotInfo.h"
00002 #include "Behaviors/Controller.h"
00003 
00004 #ifndef TGT_HAS_ARMS
00005 class ArmController : public BehaviorBase {
00006   virtual void doStart() {
00007     // This will popup a message in the ControllerGUI, if one is connected
00008     std::vector<std::string> errmsg;
00009     errmsg.push_back("The selected robot doesn't have an arm...");
00010     Controller::loadGUI("org.tekkotsu.mon.ControllerErr","",0,errmsg);
00011     stop();
00012   }
00013 };
00014 #else
00015 
00016 #include "ArmController.h"
00017 #include "Motion/MMAccessor.h"
00018 #include "Motion/ArmMC.h"
00019 #include "Shared/RobotInfo.h"
00020 #include "Motion/IKSolver.h"
00021 #include "Motion/PIDMC.h"
00022 
00023 ArmController* ArmController::theOne = NULL;
00024 
00025 void ArmController::doStart() {
00026   // Set up ArmMC, PIDMC and XLargeMotionSequenceMC for controlling and relaxing the arm
00027   SharedObject<ArmMC> arm;
00028   arm->setHold(false);
00029   armMCID = motman->addPersistentMotion(arm);
00030   SharedObject<PIDMC> pid;
00031   pidMCID = motman->addPersistentMotion(pid,MotionManager::kHighPriority);
00032   SharedObject<XLargeMotionSequenceMC> seq;
00033   seq->setHold(false);
00034   seqMCID = motman->addPersistentMotion(seq,MotionManager::kHighPriority);
00035   
00036   // Identify the initial sequence of pitch and yaw joints using alpha, theta, and jointType
00037   for (unsigned int i=0; i<NumArmJoints; i++)
00038     KJjoints[i]=NULL;
00039   gripperFrameKJ->getRoot()->buildChildMap(KJjoints, ArmOffset, NumArmJoints);
00040   
00041   int counter = 0;
00042   float alphaCum = 0;
00043   for (unsigned int i = 0; i < NumArmJoints; i++) {
00044     if (KJjoints[i] == NULL) break;
00045     if ( counter > 0 // don't worry about any rotation from base frame to first arm joint
00046          && KJjoints[i]->theta != 0 ) // we're leaving the domain of pure yaw and pitch joints: punt
00047       break;
00048     
00049     alphaCum += KJjoints[i]->alpha;
00050     if ( std::abs(alphaCum) < 1e-5  && KJjoints[i]->jointType.get() == "revolute" ) {
00051       numYawJoints++;
00052       armConfig[counter++] = 'H';
00053     }
00054     else if ( std::abs(alphaCum) > 0.99*(M_PI_2) && KJjoints[i]->jointType.get() == "revolute" ) {
00055       numPitchJoints++;
00056       armConfig[counter++] = 'V';
00057     }
00058   }
00059   linksToDisplay = numPitchJoints + numYawJoints;
00060   
00061 #ifdef TGT_LYNXARM6
00062   horScale = 20;
00063 #endif
00064 
00065   /* Find the dimensions of the arm.  Must work from the gripper
00066      backward because the kinematic chain may branch going forward (as in
00067      Calliope2 with its four-bar linkage). */
00068   fmat::Column<3> armDims;
00069   fmat::Transform gripperToArm;
00070   const KinematicJoint* armJ = kine->getKinematicJoint(ArmOffset);
00071   const KinematicJoint* tmpJ = kine->getKinematicJoint(GripperFrameOffset);
00072   if ( armJ == NULL || tmpJ == NULL )
00073     std::cout << "Error in Arm Controller: can't find arm or gripper frame!\n";
00074   else
00075     while (tmpJ != armJ && tmpJ != NULL) {
00076       tmpJ = tmpJ->getParent();
00077       gripperToArm *= tmpJ->getTo().rigidInverse();
00078     }
00079   gripperToArm = gripperToArm.rigidInverse();
00080   armDims = gripperToArm.translation();
00081   horScale = verScale = armDims.norm();
00082   horScale /= 0.85;  // why are we scaling by 1 / 0.85 ?
00083   
00084   // determine transformation from first horizontal and vertical joint to base, for IK
00085   int horIndex = 0, verIndex = 0;
00086   fmat::Transform horT, verT;
00087   if (numYawJoints != 0) {
00088     while (armConfig[horIndex] != 'H')
00089       horIndex++;
00090     while (horIndex)
00091       horT *= KJjoints[horIndex--]->getTo();
00092   }
00093   if (numPitchJoints != 0) {
00094     while (armConfig[verIndex] != 'V')
00095       verIndex++;
00096     while (verIndex)
00097       verT *= KJjoints[verIndex--]->getTo();
00098   }
00099   horToBase = horT.translation();
00100   verToBase = verT.translation();
00101   
00102   // Turn on wireless
00103   theLastOne=theOne;
00104   theOne=this;
00105   cmdsock=wireless->socket(Socket::SOCK_STREAM, 2048, 2048);
00106   wireless->setReceiver(cmdsock->sock, mechacmd_callback);
00107   wireless->setDaemon(cmdsock,true);  
00108   wireless->listen(cmdsock->sock, config->main.armControl_port);  
00109   // Open the ArmGUI on the desktop 
00110   Controller::loadGUI("org.tekkotsu.mon.ArmGUI","ArmGUI",config->main.armControl_port);
00111 }
00112 
00113 void ArmController::doStop() {
00114   Controller::closeGUI("ArmGUI");
00115   erouter->removeListener(this);
00116   wireless->setDaemon(cmdsock,false);
00117   wireless->close(cmdsock);
00118   theOne=theLastOne;
00119   motman->removeMotion(armMCID);
00120   motman->removeMotion(pidMCID);
00121   motman->removeMotion(seqMCID);
00122 }
00123 
00124 void ArmController::doEvent() {
00125   if (event->getGeneratorID()==EventBase::timerEGID) {
00126     for (unsigned int joint = 0; joint < NumArmJoints; joint++) {
00127       float jointAngle = state->outputs[ArmOffset + joint]; // When using mirage
00128       // % = (Max - Val) / (Max - Min)
00129       float normJointVal = (outputRanges[ArmOffset + joint][MaxRange] - jointAngle) /
00130         (outputRanges[ArmOffset + joint][MaxRange] - outputRanges[ArmOffset + joint][MinRange]);
00131       cmdsock->printf("Value %d %d %f\n", -1, joint, normJointVal);
00132     }
00133     
00134     computeCoords();
00135     sendCoords();
00136 
00137     // Reset the red point when the joints are reset to their original values
00138     if (displayMode == pitchAndYaw || displayMode == yawOnly)
00139       cmdsock->printf("RedValH %f %f\n", -yawCoords[numYawJoints - 1][0] / horScale, yawCoords[numYawJoints -1][1] / horScale);
00140     if (displayMode == pitchAndYaw || displayMode == pitchOnly)
00141       cmdsock->printf("RedValV %f %f\n",  pitchCoords[numPitchJoints - 1][0] / verScale, pitchCoords[numPitchJoints - 1][1] / verScale);
00142     
00143   }
00144 }
00145 
00146 // The command packet reassembly mechanism
00147 int ArmController::mechacmd_callback(char *buf, int bytes) {
00148   static char cb_buf[19];
00149   static int cb_buf_filled;
00150   
00151   // If there's an incomplete command in the command buffer, fill
00152   // up as much of the command buffer as we can and then execute it
00153   // if possible
00154   if (cb_buf_filled) {
00155     while ((cb_buf_filled < 19) && bytes) {
00156       cb_buf[cb_buf_filled++] = *buf++; // copy incoming buffer byte
00157       --bytes;        // decrement remaining byte ct.
00158     }
00159     // did we fill it? if so, execute! and mark buffer empty.
00160     if (cb_buf_filled == 9 && ((unsigned char*)cb_buf)[0] != 'x') {
00161       if (ArmController::theOne) ArmController::theOne->runCommand((unsigned char*) cb_buf);
00162       cb_buf_filled = 0;
00163     }
00164     
00165     if (cb_buf_filled == 19) {
00166       if (ArmController::theOne) ArmController::theOne->runCommand((unsigned char*) cb_buf);
00167       cb_buf_filled = 0;
00168     }
00169   }
00170   
00171   // now execute all complete bytes in the incoming buffer
00172   while (bytes >= 9) {
00173     if (((unsigned char*)buf)[0] != 'x') {
00174       if (ArmController::theOne) ArmController::theOne->runCommand((unsigned char *) buf);
00175       bytes -= 9;
00176       buf += 9;
00177     } else if (((unsigned char*)buf)[0] == 'x') {
00178       if (ArmController::theOne) ArmController::theOne->runCommand((unsigned char *) buf);
00179       bytes -= 19;
00180       buf += 19;
00181     }
00182   }
00183   
00184   // finally, store all remaining bytes in the command buffer
00185   while (bytes) {
00186     cb_buf[cb_buf_filled++] = *buf++;
00187     --bytes;
00188   }
00189   
00190   return 0;
00191 }
00192 
00193 void ArmController::runCommand(unsigned char *command) {
00194   // Extract the command parameter
00195   float param;
00196   float param2;
00197   float param3;
00198   int cmdno;
00199   unsigned char *paramp = (unsigned char *) &param;
00200   unsigned char *paramp2 = (unsigned char *) &param2;
00201   unsigned char *paramp3 = (unsigned char *) &param3;
00202   unsigned char *cmdnop = (unsigned char *) &cmdno;
00203   
00204 #if defined(BYTE_ORDER) && BYTE_ORDER==BIG_ENDIAN
00205   paramp[0] = command[4];
00206   paramp[1] = command[3];
00207   paramp[2] = command[2];
00208   paramp[3] = command[1];
00209   
00210   if (command[0] == 'x') {
00211     paramp2[0] = command[9];
00212     paramp2[1] = command[8];
00213     paramp2[2] = command[7];
00214     paramp2[3] = command[6];
00215     
00216     paramp3[0] = command[14];
00217     paramp3[1] = command[13];
00218     paramp3[2] = command[12];
00219     paramp3[3] = command[11];
00220     
00221     cmdnop[0] = command[18];
00222     cmdnop[1] = command[17];
00223     cmdnop[2] = command[16];
00224     cmdnop[3] = command[15];
00225   }
00226   else {
00227     cmdnop[0] = command[8];
00228     cmdnop[1] = command[7];
00229     cmdnop[2] = command[6];
00230     cmdnop[3] = command[5];
00231   }
00232 #else
00233   paramp[0] = command[1];
00234   paramp[1] = command[2];
00235   paramp[2] = command[3];
00236   paramp[3] = command[4];
00237   
00238   if (command[0] == 'x') {
00239     paramp2[0] = command[6];
00240     paramp2[1] = command[7];
00241     paramp2[2] = command[8];
00242     paramp2[3] = command[9];
00243     
00244     paramp3[0] = command[11];
00245     paramp3[1] = command[12];
00246     paramp3[2] = command[13];
00247     paramp3[3] = command[14];
00248     
00249     cmdnop[0] = command[15];
00250     cmdnop[1] = command[16];
00251     cmdnop[2] = command[17];
00252     cmdnop[3] = command[18];
00253   }
00254   else {
00255     cmdnop[0] = command[5];
00256     cmdnop[1] = command[6];
00257     cmdnop[2] = command[7];
00258     cmdnop[3] = command[8];
00259   }
00260   
00261 #endif // byte order
00262   
00263   // Find out what type of command this is
00264   std::cout << "ArmController command: "  << int(command[0]) << " = '" << command[0] << "'" << std::endl;
00265   switch(command[0]) {
00266   case cmdConnect:  // Connect to ArmGUI -> z command
00267     connect();
00268     break;  
00269   case cmdPoint:    // Point Picker plane #1 & plane#2-> x command
00270     pointPicked(param, param2, param3, cmdno);
00271     break;
00272   case cmdGripper:  // Gripper -> w command
00273     gripper(param, cmdno);
00274     break;    
00275   case cmdSpeed:    // Speed parameter -> y command
00276     speed = param;
00277     break;
00278   case cmdRelax:    // Relax Button -> v command
00279     relax();
00280     break;
00281   case cmdUnrelax:  // Unrelax Button -> u command
00282     unrelax();
00283     break;
00284   case cmdOrientation:  // Orientation -> o command
00285     orientationIndex = (int)param;
00286     sendReachablePoints(displayMode);
00287     break;
00288   default:
00289     setJoint(command[0], param);
00290   }
00291 }
00292 
00293 // Setup function
00294 void ArmController::connect() {
00295   // Code that validates the plane to be used in the interface
00296   if (numYawJoints > 0 && numPitchJoints > 0)
00297     displayMode = pitchAndYaw; // create both planes
00298   else if (numYawJoints > 0 && numPitchJoints == 0)
00299     displayMode = yawOnly; // create just the horizontal plane
00300   else
00301     displayMode = pitchOnly; // create just the vertical plane
00302   
00303   /*
00304    * The following option allows us to tell the ControllerGUI
00305    * what options we want to enable for the grip orientation.
00306    * orientationConfig is an integer variable that is divisible
00307    * by some or all of three prime numbers:
00308    * 
00309    * 2 - side grip
00310    * 3 - overhead grip
00311    * 5 - unconstrained grip
00312    * 
00313    * As more possible grip orientations are created, more
00314    * prime numbers can be added to this configuration,
00315    * but modifications will also need to be made java-side.
00316    * For now, supposing you want only side and overhead,
00317    * you would set orientationConfig to 2*3 = 6.
00318    */
00319   int orientationChoices;
00320 #ifdef TGT_IS_CALLIOPE5
00321   orientationChoices = 30; // side, overhead, unconstrained
00322 #else
00323   orientationChoices = 10; // side, unconstrained
00324 #endif
00325   
00326   // Send out the number of joints on the arm, display mode, and orientation configuration
00327   cmdsock->printf("NOJ %d %d %d\n", NumArmJoints, displayMode, orientationChoices);
00328   
00329   // Send the joint config
00330   for (unsigned int i = 0; i < NumArmJoints; i++)
00331     cmdsock->printf("Config %u %c\n", i, armConfig[i]);
00332   
00333   // Send info about how many of each type of joint there are.
00334   cmdsock->printf("JointTypes %d %d %d\n", numYawJoints, numPitchJoints, FingerJointsPerArm);
00335   
00336   // Send Names, Max Ouput Ranges, Min output Ranges, Current Value
00337   float jointVal, normJointVal;
00338   
00339   for (unsigned int joint = 0; joint < NumArmJoints; joint++) {
00340     jointVal = state->outputs[ArmOffset + joint];
00341     normJointVal = (outputRanges[ArmOffset + joint][MaxRange] - jointVal) /
00342       (outputRanges[ArmOffset + joint][MaxRange] - outputRanges[ArmOffset + joint][MinRange]);
00343     cmdsock->printf("JointParam %d %s %f %f %f\n", joint,
00344         outputNames[ArmOffset + joint], 
00345         outputRanges[ArmOffset + joint][MaxRange],
00346         outputRanges[ArmOffset + joint][MinRange],
00347         normJointVal);
00348   }
00349   
00350   // Compute / send
00351   computeCoords();
00352   sendCoords();
00353   if (displayMode == pitchAndYaw || displayMode == yawOnly)
00354     cmdsock->printf("RedValH %f %f\n", -yawCoords[numYawJoints - 1][0] / horScale,
00355                     yawCoords[numYawJoints -1][1] / horScale);
00356   if (displayMode == pitchAndYaw || displayMode == pitchOnly)
00357     cmdsock->printf("RedValV %f %f\n",  pitchCoords[numPitchJoints - 1][0] / verScale,
00358                     pitchCoords[numPitchJoints - 1][1] / verScale);
00359   sendReachablePoints(displayMode);
00360 }
00361 
00362 // Command to the Point Picker
00363 void ArmController::pointPicked(float param, float param2, float param3, int cmdno) {
00364 #ifdef TGT_TENTACLE
00365   //== Setup (x,y,z) so they are relative to 'ARM:5' ==//
00366 #else
00367   fmat::Column<3> target;
00368   if (param3 == 1.0) { // horizontal plane
00369     theta = std::atan2(-param,param2);
00370     target[0] = param2 * horScale + horToBase[0];
00371     target[1] = -param * horScale + horToBase[1];
00372     target[2] = z * verScale;
00373   }
00374   else if (param3 == 2.0) { // vertical plane
00375     z = param2;
00376     target[0] = (param * verScale + verToBase[0]) * std::cos(theta);
00377     target[1] = target[0] * std::tan(theta);
00378     target[2] = param2 * verScale + verToBase[2];
00379   }
00380   
00381   const KinematicJoint* tmpKJ = KJjoints[0];
00382   // transform to base
00383   while (tmpKJ->getParent() != NULL) {
00384     target += tmpKJ->getTo().translation();
00385     tmpKJ = tmpKJ->getParent();
00386   }
00387   
00388   int oriPri = orientationIndex == 2 ? 0 : 1;
00389   
00390   // construct motion sequence
00391   MMAccessor<XLargeMotionSequenceMC> seq_acc(seqMCID);
00392   
00393   // pause & clear current sequence
00394   seq_acc->pause();
00395   seq_acc->clear();
00396   
00397   // reset to current pose, to prevent jumpiness
00398   seq_acc->setTime(1);
00399   PostureEngine curpos(state);
00400   seq_acc->getPose(curpos);
00401   
00402   // calculate difference between current pose and target pose
00403   fmat::Column<3> from = kine->getPosition(GripperFrameOffset);
00404   fmat::Column<3> diff = target - from;
00405   
00406   // number of frames
00407   const int numFrames = 10;
00408   
00409   // time to get to the point (ms)
00410   const int time = 8 * diff.norm() / speed;
00411   
00412   // time step
00413   const int timeStep = time / (numFrames+3);
00414   seq_acc->advanceTime(timeStep*3);
00415   
00416   // add subsequent poses
00417   for (int i = 1; i <= numFrames; i++) {
00418     fmat::Column<3> step = from + (diff * (float)i / (float)numFrames);
00419     
00420     gripperFrameKJ->getIK().solve(fmat::ZERO3,
00421           IKSolver::Rotation(),
00422           *gripperFrameKJ,
00423           IKSolver::Point(step), 1-oriPri,
00424           IKSolver::Rotation(orientation[orientationIndex]), oriPri);
00425     
00426     for (unsigned int joint = 0; joint < linksToDisplay; joint++) {
00427       // angle, mapped from 0 - 1, based on joint limits
00428       float normJointVal;
00429       
00430       // set the new angles
00431       float q = KJjoints[joint]->getQ();
00432       
00433       // we can't be outside the limits
00434       if (q > outputRanges[ArmOffset + joint][MaxRange])
00435         normJointVal = 0;
00436       else if (q < outputRanges[ArmOffset + joint][MinRange])
00437         normJointVal = 1;
00438       
00439       // if max and min joint limit are the same, take current world state
00440       else if (outputRanges[ArmOffset + joint][MaxRange] == outputRanges[ArmOffset + joint][MinRange])
00441         normJointVal = 0.5f;
00442       
00443       // this is the normal case
00444       else
00445   // % = (Max - Val) / (Max - Min)
00446         normJointVal = (outputRanges[ArmOffset + joint][MaxRange] - q) /
00447           (outputRanges[ArmOffset + joint][MaxRange] - outputRanges[ArmOffset + joint][MinRange]);
00448       
00449       seq_acc->setOutputCmd(ArmOffset+joint, q);
00450       
00451       if (i == numFrames)
00452         cmdsock->printf("PP %d %d %f\n", cmdno++, joint, normJointVal);
00453     }
00454     
00455     seq_acc->advanceTime(timeStep);
00456   }
00457   
00458   seq_acc->play();
00459   
00460   computeCoords();
00461   sendCoords();
00462   // Reset the red point in the other plane (the one the user did not just click on)
00463   if (param3 == 1.0 && displayMode == pitchAndYaw)
00464     cmdsock->printf("RedValV %f %f\n",  pitchCoords[numPitchJoints - 1][0] / verScale, pitchCoords[numPitchJoints - 1][1] / verScale);
00465   else if (param3 == 2.0 && displayMode == pitchAndYaw)
00466     cmdsock->printf("RedValH %f %f\n", -yawCoords[numYawJoints - 1][0] / horScale, yawCoords[numYawJoints -1][1] / horScale);
00467 
00468   // Allow 2 seconds between each update
00469   if (reachablePointsDelay.Age().Value() > 0.5) {
00470     sendReachablePoints(param3 == 1.0f ? pitchOnly : yawOnly);
00471     reachablePointsDelay.Set();
00472   }
00473   
00474 #endif
00475 }
00476 
00477 void ArmController::gripper(float param, int cmdno) {
00478   // Moving the ArmGUI's gripper slider generates a w command, which
00479   // takes us here.  We decide which joints to move (there may be
00480   // multiple fingers) and send one or two Gripper commands back to
00481   // the ArmGUI. It responds to these Gripper commands by moving the
00482   // individual finger sliders, which in turn send individual joint
00483   // movement commands back to the ArmController.  These commands have
00484   // an offset of 30 to mark them as gripper-related so we don't try
00485   // to set the red and green dots.
00486 #ifdef TGT_HAS_GRIPPER
00487   float gripperQ = (1.0f - param) / 2.0f;
00488 #  ifdef TGT_HAS_FINGERS
00489   float right = gripperQ;
00490   float left = 1.0f - gripperQ;
00491   
00492   cmdsock->printf("Gripper %d %d %f\n", cmdno, RightFingerOffset - ArmOffset, right);
00493   cmdsock->printf("Gripper %d %d %f\n", cmdno, LeftFingerOffset - ArmOffset, left);
00494 #  else
00495   cmdsock->printf("Gripper %d %d %f\n", cmdno, GripperOffset - ArmOffset, gripperQ);
00496 #  endif
00497 #endif
00498 }
00499 
00500 void ArmController::relax() {
00501   MMAccessor<PIDMC> relaxer(pidMCID);
00502   for (unsigned int joint = 0; joint < NumArmJoints; joint++)
00503     relaxer->setJointPowerLevel(ArmOffset + joint, 0);
00504   processEvent(EventBase(EventBase::timerEGID,1,EventBase::statusETID,0));
00505   erouter->addTimer(this,0,500);
00506 }
00507 
00508 void ArmController::unrelax() {
00509   erouter->removeTimer(this);
00510   MMAccessor<PIDMC> unrelaxer(pidMCID);
00511   for (unsigned int joint = 0; joint < NumArmJoints; joint++) 
00512     unrelaxer->setJointPowerLevel(ArmOffset + joint, 1.0);
00513 }
00514 
00515 void ArmController::setJoint(unsigned int joint, float angle) {
00516   unsigned int jointNo = joint < 30 ? joint : (joint - 30);
00517   if (jointNo >= NumArmJoints) {
00518     std::cerr << "Illegal command to ArmController " << joint << " " << jointNo << " "  << NumArmJoints << std::endl;
00519     return;
00520   }
00521   
00522   // enclose the motion sequence so that it gets checked back in before we get to the ArmMC
00523   {
00524     // if there's a motion sequence going on, stop it.
00525     MMAccessor<XLargeMotionSequenceMC> seq_acc(seqMCID);
00526     
00527     if (seq_acc->isPlaying()) {
00528       seq_acc->pause();
00529       seq_acc->clear();
00530       
00531       // set joints to reflect WorldState
00532       for (unsigned int i = 0; KJjoints[i] != NULL; i++)
00533   KJjoints[i]->setQ(kine->getKinematicJoint(ArmOffset + i)->getQ());
00534     }
00535   }
00536   
00537   MMAccessor<ArmMC> arm(armMCID);
00538   arm->setMaxSpeed(jointNo, speed);
00539   // Val = %*Min + (1 - %)Max
00540   float jointVal = angle * outputRanges[ArmOffset + jointNo][MinRange] + (1.0f - angle) * outputRanges[ArmOffset + jointNo][MaxRange];
00541   arm->setJointValue(jointNo, jointVal); // change the value of the arm physically
00542   
00543   if (KJjoints[jointNo] != NULL)
00544     KJjoints[jointNo]->setQ(jointVal);
00545   
00546   computeCoords();
00547   sendCoords();
00548   
00549   if (joint < NumArmJoints) {
00550     if (displayMode == pitchAndYaw || displayMode == yawOnly)
00551       cmdsock->printf("RedValH %f %f\n", -yawCoords[numYawJoints - 1][0] / horScale, yawCoords[numYawJoints -1][1] / horScale);
00552     if (displayMode == pitchAndYaw || displayMode == pitchOnly)
00553       cmdsock->printf("RedValV %f %f\n",  pitchCoords[numPitchJoints - 1][0] / verScale, pitchCoords[numPitchJoints - 1][1] / verScale);
00554   }
00555 }
00556 
00557 // Validate this function with the projection of joint
00558 void ArmController::computeCoords() {
00559   // Works for the Calliope, Chiara, Chiara2 and Handeye and almost for the Lynxarm. 
00560   if ( displayMode != pitchAndYaw ) return;
00561   fmat::Column<3> baseHorizontal;
00562   fmat::Column<3> baseVertical;
00563   
00564   // Looking for the first horizontal joint 
00565   for (unsigned int i = 0; i < linksToDisplay; i++) {
00566     if (armConfig[i] == 'H') {
00567       baseHorizontal = KJjoints[i]->getWorldPosition();
00568       break;
00569     }
00570   }
00571   // Looking for the first vertical joint 
00572   for (unsigned int i = 0; i < linksToDisplay; i++) {
00573     if (armConfig[i] == 'V') {
00574       baseVertical = KJjoints[i]->getWorldPosition();
00575       break;
00576     }
00577   }
00578   
00579   unsigned int yawCount = 0, pitchCount = 0;
00580   
00581   // Calculate the coordinates without projections
00582   for (unsigned int links = 0; links < linksToDisplay; links++) {
00583     if (armConfig[links] == 'H') {
00584       const KinematicJoint* relPosJoint;
00585       if (yawCount == numYawJoints - 1)
00586         relPosJoint = gripperFrameKJ;
00587       else
00588         relPosJoint = KJjoints[links+1];
00589       fmat::Column<3> relPos = relPosJoint->getWorldPosition() - baseHorizontal;
00590       yawCoords[yawCount][0] = relPos[1]; // y-axis 
00591       yawCoords[yawCount][1] = relPos[0]; // x-axis
00592       yawCount++;
00593     }
00594     else if (armConfig[links] == 'V') {
00595       const KinematicJoint* relPosJoint;
00596       if (pitchCount == numPitchJoints - 1)
00597         relPosJoint = gripperFrameKJ;
00598       else
00599         relPosJoint = KJjoints[links+1];
00600       fmat::Column<3> relPos = relPosJoint->getWorldPosition() - baseVertical;
00601       pitchCoords[pitchCount][0] = fmat::SubVector<2>(relPos).norm() *
00602         (yawCoords[yawCount-1][1] * relPos[0] > 0 ? 1 : -1); // x-axis
00603       pitchCoords[pitchCount][1] = relPos[2]; // z-axis
00604       pitchCount++;
00605     }
00606   }
00607 }
00608 
00609 void ArmController::sendCoords() {
00610   // Send out the coordinates of the links to planes 
00611   if (displayMode == pitchAndYaw || displayMode == yawOnly) {
00612     for (unsigned int links = 0; links < numYawJoints; links++)
00613       cmdsock->printf("CoordH %d %f %f\n", links, -yawCoords[links][0]/horScale, yawCoords[links][1]/horScale);
00614     cmdsock->printf("GreenValH %f %f\n", -yawCoords[numYawJoints - 1][0] / horScale, yawCoords[numYawJoints - 1][1] / horScale);
00615   }
00616   if (displayMode == pitchAndYaw || displayMode == pitchOnly) {
00617     for (unsigned int links = 0; links < numPitchJoints; links++)
00618       cmdsock->printf("CoordV %d %f %f\n", links, pitchCoords[links][0] / verScale,
00619                       pitchCoords[links][1] / verScale);
00620     cmdsock->printf("GreenValV %f %f\n", pitchCoords[numPitchJoints - 1][0] / verScale,
00621                     pitchCoords[numPitchJoints - 1][1] / verScale);
00622   }
00623 }
00624 
00625 void ArmController::sendReachablePoints(DisplayMode_t d) {
00626   //float delta = 0.025f;
00627   float delta = 0.1f;
00628   
00629   if (d == yawOnly || d == pitchAndYaw) {
00630     // clear the points first
00631     cmdsock->printf("ClearPtsH\n");
00632     
00633     // Send spots of success
00634     for (float x = -1; x <= 1; x += delta) {
00635       for (float y = 0; y <= 1; y += delta) {
00636   fmat::Column<3> target;
00637   target[0] = y * horScale + horToBase[0];
00638   target[1] = -x * horScale + horToBase[1];
00639   target[2] = z * verScale;
00640         
00641   const KinematicJoint* tmpKJ = KJjoints[0];
00642   // transform to base
00643   while (tmpKJ->getParent() != NULL) {
00644     target += tmpKJ->getTo().translation();
00645     tmpKJ = tmpKJ->getParent();
00646   }
00647         
00648   int oriPri = orientationIndex == 2 ? 0 : 1;
00649   // perform IK
00650   bool success = successJ->getIK().solve(fmat::Column<3>(),
00651                  IKSolver::Rotation(),
00652                  *successJ,
00653                  IKSolver::Point(target), 1-oriPri,
00654                  IKSolver::Rotation(orientation[orientationIndex]), oriPri);
00655   if (success)
00656     cmdsock->printf("SuccessH %f %f\n", x, y);
00657       }
00658     }
00659     cmdsock->printf("RepaintH\n");
00660 
00661   }
00662   if (d == pitchOnly || d == pitchAndYaw) {
00663     // clear the points first
00664     cmdsock->printf("ClearPtsV\n");
00665     
00666     // Send spots of success
00667     for (float x = 0; x <= 1; x += delta) {
00668       for (float y = -1; y <= 1; y += delta) {
00669   fmat::Column<3> target;
00670   target[0] = x * verScale + verToBase[0] * std::cos(theta);
00671   target[1] = target[0] * std::tan(theta);
00672   target[2] = y * verScale + verToBase[2];
00673         
00674   const KinematicJoint* tmpKJ = KJjoints[0];
00675   // transform to base
00676   while (tmpKJ->getParent() != NULL) {
00677     target += tmpKJ->getTo().translation();
00678     tmpKJ = tmpKJ->getParent();
00679   }
00680         
00681   int oriPri = orientationIndex == 2 ? 0 : 1;
00682   // perform IK
00683   bool success = successJ->getIK().solve(fmat::Column<3>(),
00684                  IKSolver::Rotation(),
00685                  *successJ,
00686                  IKSolver::Point(target), 1-oriPri,
00687                  IKSolver::Rotation(orientation[orientationIndex]), oriPri);
00688   if (success)
00689     cmdsock->printf("SuccessV %f %f\n", x / std::cos(theta), y);
00690       }
00691     }
00692     cmdsock->printf("RepaintV\n");
00693   }
00694 }
00695 
00696 #endif // TGT_HAS_ARMS
00697 
00698 REGISTER_BEHAVIOR_MENU_OPT(ArmController,"TekkotsuMon",BEH_NONEXCLUSIVE);
00699 
00700 /*! @file
00701  * @brief Implements ArmController, listens to control commands coming in from the command port for remotely controlling the arm
00702  * @author tss (Creator)
00703  */

Tekkotsu v5.1CVS
Generated Mon May 9 04:58:35 2016 by Doxygen 1.6.3