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
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/PIDMC.h"
00021
00022 ArmController* ArmController::theOne = NULL;
00023
00024 void ArmController::doStart() {
00025
00026 SharedObject<ArmMC> arm;
00027 arm->setHold(false);
00028 arm_id = motman->addPersistentMotion(arm);
00029 SharedObject<PIDMC> pid;
00030 pidMCID = motman->addPersistentMotion(pid,MotionManager::kHighPriority);
00031
00032
00033 gripperFrameKJ->getRoot()->buildChildMap(KJjoints, ArmOffset, NumArmJoints);
00034
00035 int counter = 0;
00036 float alphaCum = 0;
00037 for (unsigned int i = 0; i < NumArmJoints; i++) {
00038 if (KJjoints[i] == NULL) break;
00039 if ( counter > 0
00040 && KJjoints[i]->theta != 0 )
00041 break;
00042
00043 alphaCum += KJjoints[i]->alpha;
00044 if ( std::abs(alphaCum) < 1e-5 && KJjoints[i]->jointType.get() == "revolute" ) {
00045 numYawJoints++;
00046 armConfig[counter++] = 'H';
00047 }
00048 else if ( std::abs(alphaCum) > 0.99*(M_PI_2) && KJjoints[i]->jointType.get() == "revolute" ) {
00049 numPitchJoints++;
00050 armConfig[counter++] = 'V';
00051 }
00052 }
00053 linksToDisplay = numPitchJoints + numYawJoints;
00054
00055 #ifdef TGT_LYNXARM6
00056 horScale = 20;
00057 #endif
00058
00059
00060
00061
00062 fmat::Column<3> armDims;
00063 fmat::Transform gripperToArm;
00064 const KinematicJoint* armJ = kine->getKinematicJoint(ArmOffset);
00065 const KinematicJoint* tmpJ = kine->getKinematicJoint(GripperFrameOffset);
00066 if ( armJ == NULL || tmpJ == NULL )
00067 std::cout << "Error in Arm Controller: can't find arm or gripper frame!\n";
00068 else
00069 while (tmpJ != armJ && tmpJ != NULL) {
00070 tmpJ = tmpJ->getParent();
00071 gripperToArm *= tmpJ->getTo().rigidInverse();
00072 }
00073 gripperToArm = gripperToArm.rigidInverse();
00074 armDims = gripperToArm.translation();
00075 horScale = verScale = armDims.norm();
00076 horScale /= 0.85;
00077
00078
00079 int horIndex = 0, verIndex = 0;
00080 fmat::Transform horT, verT;
00081 if (numYawJoints != 0) {
00082 while (armConfig[horIndex] != 'H')
00083 horIndex++;
00084 while (horIndex)
00085 horT *= KJjoints[horIndex--]->getTo();
00086 }
00087 if (numPitchJoints != 0) {
00088 while (armConfig[verIndex] != 'V')
00089 verIndex++;
00090 while (verIndex)
00091 verT *= KJjoints[verIndex--]->getTo();
00092 }
00093 horToBase = horT.translation();
00094 verToBase = verT.translation();
00095
00096
00097 theLastOne=theOne;
00098 theOne=this;
00099 cmdsock=wireless->socket(Socket::SOCK_STREAM, 2048, 2048);
00100 wireless->setReceiver(cmdsock->sock, mechacmd_callback);
00101 wireless->setDaemon(cmdsock,true);
00102 wireless->listen(cmdsock->sock, config->main.armControl_port);
00103
00104 Controller::loadGUI("org.tekkotsu.mon.ArmGUI","ArmGUI",config->main.armControl_port);
00105 }
00106
00107 void ArmController::doStop() {
00108 Controller::closeGUI("ArmGUI");
00109 erouter->removeListener(this);
00110 wireless->setDaemon(cmdsock,false);
00111 wireless->close(cmdsock);
00112 theOne=theLastOne;
00113 motman->removeMotion(arm_id);
00114 motman->removeMotion(pidMCID);
00115 }
00116
00117 void ArmController::doEvent() {
00118 if (event->getGeneratorID()==EventBase::timerEGID) {
00119 float normJointVal, jointAngle;
00120 for (unsigned int joint = 0; joint < NumArmJoints; joint++) {
00121 jointAngle = state->outputs[ArmOffset + joint];
00122
00123 normJointVal = (outputRanges[ArmOffset + joint][MaxRange] - jointAngle)/(outputRanges[ArmOffset + joint][MaxRange] - outputRanges[ArmOffset + joint][MinRange]);
00124 cmdsock->printf("Value %d %d %f\n", -1, joint, normJointVal );
00125 }
00126
00127 computeCoords();
00128 sendCoords();
00129
00130
00131 if (displayMode == pitchAndYaw) {
00132 cmdsock->printf("RValue %f %f\n", -yawCoords[numYawJoints -1][0] / horScale, yawCoords[numYawJoints -1][1] / horScale);
00133 cmdsock->printf("RValue1 %f %f\n", pitchCoords[numPitchJoints - 1][0] / verScale, pitchCoords[numPitchJoints - 1][1] / verScale);
00134 }
00135
00136
00137 if (displayMode == yawOnly) {
00138 cmdsock->printf("RValue %f %f\n", -yawCoords[numYawJoints -1][0] / horScale, yawCoords[numYawJoints -1][1] / horScale);
00139 }
00140
00141
00142 if (displayMode == pitchOnly) {
00143 cmdsock->printf("Rvalue1 %f %f\n", pitchCoords[numPitchJoints - 1][0] / verScale, pitchCoords[numPitchJoints - 1][1] / verScale);
00144 }
00145 }
00146 }
00147
00148
00149 int ArmController::mechacmd_callback(char *buf, int bytes) {
00150 static char cb_buf[19];
00151 static int cb_buf_filled;
00152
00153
00154
00155
00156 if (cb_buf_filled) {
00157 while ((cb_buf_filled < 19) && bytes) {
00158 cb_buf[cb_buf_filled++] = *buf++;
00159 --bytes;
00160 }
00161
00162 if (cb_buf_filled == 9 && ((unsigned char*)cb_buf)[0] != 'x') {
00163 if (ArmController::theOne) ArmController::theOne->runCommand((unsigned char*) cb_buf);
00164 cb_buf_filled = 0;
00165 }
00166
00167 if (cb_buf_filled == 19) {
00168 if (ArmController::theOne) ArmController::theOne->runCommand((unsigned char*) cb_buf);
00169 cb_buf_filled = 0;
00170 }
00171 }
00172
00173
00174 while (bytes >= 9) {
00175 if (((unsigned char*)buf)[0] != 'x') {
00176 if (ArmController::theOne) ArmController::theOne->runCommand((unsigned char *) buf);
00177 bytes -= 9;
00178 buf += 9;
00179 } else if (((unsigned char*)buf)[0] == 'x') {
00180 if (ArmController::theOne) ArmController::theOne->runCommand((unsigned char *) buf);
00181 bytes -= 19;
00182 buf += 19;
00183 }
00184 }
00185
00186
00187 while (bytes) {
00188 cb_buf[cb_buf_filled++] = *buf++;
00189 --bytes;
00190 }
00191
00192 return 0;
00193 }
00194
00195 void ArmController::runCommand(unsigned char *command) {
00196
00197 float param;
00198 float param2;
00199 float param3;
00200 int cmdno;
00201 unsigned char *paramp = (unsigned char *) ¶m;
00202 unsigned char *paramp2 = (unsigned char *) ¶m2;
00203 unsigned char *paramp3 = (unsigned char *) ¶m3;
00204 unsigned char *cmdnop = (unsigned char *) &cmdno;
00205
00206 #if defined(BYTE_ORDER) && BYTE_ORDER==BIG_ENDIAN
00207 paramp[0] = command[4];
00208 paramp[1] = command[3];
00209 paramp[2] = command[2];
00210 paramp[3] = command[1];
00211
00212 if (command[0] == 'x') {
00213 paramp2[0] = command[9];
00214 paramp2[1] = command[8];
00215 paramp2[2] = command[7];
00216 paramp2[3] = command[6];
00217
00218 paramp3[0] = command[14];
00219 paramp3[1] = command[13];
00220 paramp3[2] = command[12];
00221 paramp3[3] = command[11];
00222
00223 cmdnop[0] = command[18];
00224 cmdnop[1] = command[17];
00225 cmdnop[2] = command[16];
00226 cmdnop[3] = command[15];
00227 }
00228 else {
00229 cmdnop[0] = command[8];
00230 cmdnop[1] = command[7];
00231 cmdnop[2] = command[6];
00232 cmdnop[3] = command[5];
00233 }
00234 #else
00235 paramp[0] = command[1];
00236 paramp[1] = command[2];
00237 paramp[2] = command[3];
00238 paramp[3] = command[4];
00239
00240 if (command[0] == 'x') {
00241 paramp2[0] = command[6];
00242 paramp2[1] = command[7];
00243 paramp2[2] = command[8];
00244 paramp2[3] = command[9];
00245
00246 paramp3[0] = command[11];
00247 paramp3[1] = command[12];
00248 paramp3[2] = command[13];
00249 paramp3[3] = command[14];
00250
00251 cmdnop[0] = command[15];
00252 cmdnop[1] = command[16];
00253 cmdnop[2] = command[17];
00254 cmdnop[3] = command[18];
00255 }
00256 else {
00257 cmdnop[0] = command[5];
00258 cmdnop[1] = command[6];
00259 cmdnop[2] = command[7];
00260 cmdnop[3] = command[8];
00261 }
00262
00263 #endif // byte order
00264
00265
00266 switch(command[0]) {
00267 case cmdConnect:
00268 connect();
00269 break;
00270 case cmdPoint:
00271 pointPicked(param, param2, param3, cmdno);
00272 break;
00273 case cmdGripper:
00274 gripper(param, cmdno);
00275 break;
00276 case cmdSpeed:
00277 speed = param;
00278 break;
00279 case cmdRelax:
00280 relax();
00281 break;
00282 case cmdUnrelax:
00283 unrelax();
00284 break;
00285 case cmdOrientation:
00286 setOrientation((int)param);
00287 break;
00288 default: {
00289 setJoint(command[0], param);
00290 }
00291 }
00292 }
00293
00294
00295 void ArmController::connect() {
00296
00297 if (numYawJoints > 0 && numPitchJoints > 0)
00298 displayMode = pitchAndYaw;
00299 else if (numYawJoints > 0 && numPitchJoints == 0)
00300 displayMode = yawOnly;
00301 else
00302 displayMode = pitchOnly;
00303
00304
00305 cmdsock->printf("NOJ %d %d\n", NumArmJoints, displayMode);
00306
00307
00308 for (unsigned int i = 0; i < NumArmJoints; i++)
00309 cmdsock->printf("Config %u %c\n", i, armConfig[i]);
00310
00311
00312 cmdsock->printf("JointTypes %d %d\n", numYawJoints, numPitchJoints);
00313
00314
00315 float jointVal, normJointVal;
00316
00317 for (unsigned int joint = 0; joint < NumArmJoints; joint++) {
00318 jointVal = state->outputs[ArmOffset + joint];
00319 normJointVal = (outputRanges[ArmOffset + joint][MaxRange] - jointVal) /
00320 (outputRanges[ArmOffset + joint][MaxRange] - outputRanges[ArmOffset + joint][MinRange]);
00321 cmdsock->printf("JointParam %d %s %f %f %f\n", joint,
00322 outputNames[ArmOffset + joint],
00323 outputRanges[ArmOffset + joint][MaxRange],
00324 outputRanges[ArmOffset + joint][MinRange],
00325 normJointVal);
00326 }
00327
00328
00329 if (numYawJoints > 0)
00330 cmdsock->printf("IRGValue %f %f\n", -yawCoords[numYawJoints - 1][0] / horScale, yawCoords[numYawJoints - 1][1] / horScale);
00331 if (numPitchJoints > 0)
00332 cmdsock->printf("IRGValue1 %f %f\n", pitchCoords[numPitchJoints - 1][0] / verScale, pitchCoords[numPitchJoints - 1][1] / verScale);
00333
00334
00335 computeCoords();
00336 sendCoords();
00337
00338 }
00339
00340
00341 void ArmController::pointPicked(float param, float param2, float param3, int cmdno) {
00342 #if TGT_TENTACLE
00343
00344 #else
00345 fmat::Column<3> tgtPoint;
00346 if (param3 == 1.0) {
00347 theta = std::atan2(-param,param2);
00348 tgtPoint[0] = param2 * horScale + horToBase[0];
00349 tgtPoint[1] = -param * horScale + horToBase[1];
00350 tgtPoint[2] = z * verScale;
00351 }
00352 else if (param3 == 2.0) {
00353 z = param2;
00354 tgtPoint[0] = (param * verScale + verToBase[0]) * std::cos(theta);
00355 tgtPoint[1] = tgtPoint[0] * std::tan(theta);
00356 tgtPoint[2] = param2 * verScale + verToBase[2];
00357 }
00358
00359 const KinematicJoint* tmpKJ = KJjoints[0];
00360
00361 while (tmpKJ->getParent() != NULL) {
00362 tgtPoint += tmpKJ->getTo().translation();
00363 tmpKJ = tmpKJ->getParent();
00364 }
00365
00366
00367
00368 gripperFrameKJ->getIK().solve(fmat::Column<3>(),
00369 IKSolver::Rotation(),
00370 *gripperFrameKJ,
00371 IKSolver::Point(tgtPoint), 1,
00372 IKSolver::Rotation(orientation[orientationIndex]), 0);
00373
00374 for (unsigned int joint = 0; joint < linksToDisplay; joint++) {
00375
00376 float normJointVal;
00377
00378
00379 float q = KJjoints[joint]->getQ();
00380
00381
00382 if (q > outputRanges[ArmOffset + joint][MaxRange])
00383 normJointVal = 0;
00384 else if (q < outputRanges[ArmOffset + joint][MinRange])
00385 normJointVal = 1;
00386
00387
00388 else if (outputRanges[ArmOffset + joint][MaxRange] == outputRanges[ArmOffset + joint][MinRange])
00389 normJointVal = state->outputs[ArmOffset + joint];
00390
00391
00392 else
00393
00394 normJointVal = (outputRanges[ArmOffset + joint][MaxRange] - q)/(outputRanges[ArmOffset + joint][MaxRange] - outputRanges[ArmOffset + joint][MinRange]);
00395
00396 cmdsock->printf("CValue %d %d %f\n", cmdno, joint, normJointVal);
00397 }
00398 #endif
00399 }
00400
00401 void ArmController::gripper(float param, int cmdno) {
00402 #ifdef TGT_HAS_GRIPPER
00403 float gripperQ = (1.0f - param) / 2.0f;
00404 # ifdef TGT_HAS_FINGERS
00405 float right = gripperQ;
00406 float left = 1.0f - gripperQ;
00407
00408 cmdsock->printf("CValue %d %d %f\n", cmdno, RightFingerOffset - ArmOffset, right);
00409 cmdsock->printf("CValue %d %d %f\n", cmdno, LeftFingerOffset - ArmOffset, left);
00410 # else
00411 cmdsock->printf("CValue %d %d %f\n", cmdno, GripperOffset - ArmOffset, gripperQ);
00412 # endif
00413 #endif
00414 }
00415
00416 void ArmController::relax() {
00417 MMAccessor<PIDMC> relaxer(pidMCID);
00418 for (unsigned int joint = 0; joint < NumArmJoints; joint++)
00419 relaxer->setJointPowerLevel(ArmOffset + joint, 0);
00420 processEvent(EventBase(EventBase::timerEGID,1,EventBase::statusETID,0));
00421 erouter->addTimer(this,0,500);
00422 }
00423
00424 void ArmController::unrelax() {
00425 erouter->removeTimer(this);
00426 MMAccessor<PIDMC> unrelaxer(pidMCID);
00427 for (unsigned int joint = 0; joint < NumArmJoints; joint++)
00428 unrelaxer->setJointPowerLevel(ArmOffset + joint, 1.0);
00429 }
00430
00431 void ArmController::setOrientation(int index) {
00432 orientationIndex = index;
00433 }
00434
00435 void ArmController::setJoint(unsigned int joint, float angle) {
00436 unsigned int jointNo = joint < NumArmJoints ? joint : joint - NumArmJoints;
00437 if (jointNo >= NumArmJoints) {
00438 std::cerr << "Illegal command to ArmController " << joint << " " << jointNo << " " << NumArmJoints << std::endl;
00439 return;
00440 }
00441
00442 MMAccessor<ArmMC> arm(arm_id);
00443 arm->setMaxSpeed(jointNo, speed);
00444
00445 float jointVal = -( angle * (outputRanges[ArmOffset + jointNo][MaxRange] - outputRanges[ArmOffset + jointNo][MinRange]) ) + outputRanges[ArmOffset + jointNo][MaxRange];
00446 arm->setJointValue(jointNo, jointVal);
00447
00448 if (KJjoints[jointNo] != NULL)
00449 KJjoints[jointNo]->setQ(jointVal);
00450
00451 computeCoords();
00452 sendCoords();
00453
00454 if (joint < NumArmJoints) {
00455 switch (displayMode) {
00456 case pitchAndYaw:
00457
00458 cmdsock->printf("RValue %f %f\n", -yawCoords[numYawJoints - 1][0] / horScale, yawCoords[numYawJoints - 1][1] / horScale);
00459 cmdsock->printf("RValue1 %f %f\n", pitchCoords[numPitchJoints - 1][0] / verScale, pitchCoords[numPitchJoints - 1][1] / verScale);
00460 break;
00461 case yawOnly:
00462
00463 cmdsock->printf("RValue %f %f\n", -yawCoords[numYawJoints - 1][0] / horScale, yawCoords[numYawJoints - 1][1] / horScale);
00464 break;
00465 case pitchOnly:
00466
00467 cmdsock->printf("RValue1 %f %f\n", pitchCoords[numPitchJoints - 1][0] / verScale, pitchCoords[numPitchJoints - 1][1] / verScale);
00468 break;
00469 }
00470 }
00471 }
00472
00473
00474 void ArmController::computeCoords() {
00475
00476 fmat::Column<3> baseHorizontal;
00477 fmat::Column<3> baseVertical;
00478
00479
00480 for (unsigned int i = 0; i < linksToDisplay; i++) {
00481 if (armConfig[i] == 'H') {
00482 baseHorizontal = KJjoints[i]->getWorldPosition();
00483 break;
00484 }
00485 }
00486
00487 for (unsigned int i = 0; i < linksToDisplay; i++) {
00488 if (armConfig[i] == 'V') {
00489 baseVertical = KJjoints[i]->getWorldPosition();
00490 break;
00491 }
00492 }
00493
00494 unsigned int yawCount = 0, pitchCount = 0;
00495
00496
00497 for (unsigned int links = 0; links < linksToDisplay; links++) {
00498 if (armConfig[links] == 'H') {
00499 KinematicJoint* relPosJoint;
00500 if (yawCount == numYawJoints - 1)
00501 relPosJoint = gripperFrameKJ;
00502 else
00503 relPosJoint = KJjoints[links+1];
00504 fmat::Column<3> relPos = relPosJoint->getWorldPosition() - baseHorizontal;
00505 yawCoords[yawCount][0] = relPos[1];
00506 yawCoords[yawCount][1] = relPos[0];
00507 yawCount++;
00508 }
00509 else if (armConfig[links] == 'V') {
00510 KinematicJoint* relPosJoint;
00511 if (pitchCount == numPitchJoints - 1)
00512 relPosJoint = gripperFrameKJ;
00513 else
00514 relPosJoint = KJjoints[links+1];
00515 fmat::Column<3> relPos = relPosJoint->getWorldPosition() - baseVertical;
00516 pitchCoords[pitchCount][0] = fmat::SubVector<2>(relPos).norm() * (yawCoords[yawCount-1][1] * relPos[0] > 0 ? 1 : -1);
00517 pitchCoords[pitchCount][1] = relPos[2];
00518 pitchCount++;
00519 }
00520 }
00521 }
00522
00523 void ArmController::sendCoords() {
00524
00525 switch (displayMode) {
00526 case pitchAndYaw:
00527 for (unsigned int links = 0; links < numYawJoints; links++)
00528 cmdsock->printf("Coord %d %f %f\n", links, -yawCoords[links][0]/horScale, yawCoords[links][1]/horScale);
00529 for (unsigned int links = 0; links < numPitchJoints; links++)
00530 cmdsock->printf("Coord1 %d %f %f\n", links, pitchCoords[links][0] / verScale, pitchCoords[links][1] / verScale);
00531
00532 cmdsock->printf("GValue %f %f\n", -yawCoords[numYawJoints - 1][0] / horScale, yawCoords[numYawJoints - 1][1] / horScale);
00533
00534
00535 cmdsock->printf("GValue1 %f %f\n", pitchCoords[numPitchJoints - 1][0] / verScale, pitchCoords[numPitchJoints - 1][1] / verScale);
00536 break;
00537 case yawOnly:
00538 for (unsigned int links = 0; links < numYawJoints; links++)
00539 cmdsock->printf("Coord %d %f %f\n", links, -yawCoords[links][0]/horScale, yawCoords[links][1]/horScale);
00540
00541 cmdsock->printf("GValue %f %f\n", -yawCoords[numYawJoints - 1][0] / horScale, yawCoords[numYawJoints - 1][1] / horScale);
00542 break;
00543 case pitchOnly:
00544 for (unsigned int links = 0; links < numPitchJoints; links++)
00545 cmdsock->printf("Coord1 %d %f %f\n", links, pitchCoords[links][0] / verScale, pitchCoords[links][1] / verScale);
00546
00547 cmdsock->printf("GValue1 %f %f\n", pitchCoords[numPitchJoints - 1][0] / verScale, pitchCoords[numPitchJoints - 1][1] / verScale);
00548 }
00549 }
00550
00551 #endif // TGT_HAS_ARMS
00552
00553 REGISTER_BEHAVIOR_MENU_OPT(ArmController,"TekkotsuMon",BEH_NONEXCLUSIVE);
00554
00555
00556
00557
00558