00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026 #include "gloveInterface.h"
00027
00028 #include "robot.h"
00029
00030 #ifdef HARDWARE_LIB
00031 #include "CyberGlove.h"
00032 #else
00033 #define N_SENSOR_VALUES 24
00034 #endif
00035
00036 #include "world.h"
00037 #include "matvec3D.h"
00038 #include "jacobian.h"
00039
00040 #ifdef MKL
00041 #include "mkl_wrappers.h"
00042 #else
00043 #include "lapack_wrappers.h"
00044 #endif
00045
00046 #include "debug.h"
00047
00048
00049 void CalibrationPose::init(int size)
00050 {
00051 if (size < 0) {
00052 fprintf(stderr,"Wrong size of calibration pose\n");
00053 mSize = 0;
00054 } else {
00055 mSize = size;
00056 }
00057 if (mSize>0) {
00058 jointValues = new double[size];
00059 sensorValues = new int[size];
00060 sensorMap = new int[size];
00061 }
00062 recordedDistance = 0;
00063 mSize = size;
00064 jointsSet = false;
00065 sensorsSet = false;
00066 mapSet = false;
00067 poseSet = false;
00068 mTransf = transf::IDENTITY;
00069 }
00070
00071 CalibrationPose::CalibrationPose(int size)
00072 {
00073 init(size);
00074 }
00075
00076 CalibrationPose::CalibrationPose(int size, double *joints, int *map)
00077 {
00078 init(size);
00079 setAllJointValues(joints);
00080 for (int i=0; i<size; i++) {
00081 jointValues[i] = jointValues[i] * 3.14159 / 180.0;
00082 }
00083 setAllMaps(map);
00084 }
00085
00086 CalibrationPose::~CalibrationPose()
00087 {
00088 delete [] jointValues;
00089 delete [] sensorValues;
00090 delete [] sensorMap;
00091 }
00092
00093 void CalibrationPose::readFromFile(FILE *fp)
00094 {
00095 int val;
00096 float floatVal;
00097 int j;
00098
00099 if(fscanf(fp,"%d",&mSize) <=0){
00100 DBGA("CalibrationPose::readFromFile - Failed to read calibration size");
00101 return;
00102 }
00103 init(mSize);
00104
00105 if(fscanf(fp,"%f",&floatVal) <= 0) {
00106 DBGA("CalibrationPose::readFromFile - Failed to read recorded distance");
00107 return;
00108 }
00109 recordedDistance = floatVal;
00110 if(fscanf(fp,"%d",&val)) {
00111 DBGA("CalibrationPose::readFromFile - Failed to read sensor number");
00112 return;
00113 }
00114
00115 if (val) {
00116 for (j=0; j<mSize; j++) {
00117 if(fscanf(fp,"%d",&val) <= 0) {
00118 DBGA("CalibrationPose::readFromFile - Failed to read sensor value");
00119 return;
00120 }
00121 setSensorValue(j,val);
00122 }
00123 sensorsSet = true;
00124 } else sensorsSet = false;
00125
00126 if (fscanf(fp,"%d",&val) <= 0) {
00127 DBGA("CalibrationPose::readFromFile - Failed to read map size");
00128 return;
00129 }
00130
00131 if (val) {
00132 for (j=0; j<mSize; j++) {
00133 if(fscanf(fp,"%d",&val) <= 0) {
00134 DBGA("CalibrationPose::readFromFile - Failed to read map value");
00135 return;
00136 }
00137
00138 setMap(j,val);
00139 }
00140 mapSet = true;
00141 }
00142 else mapSet = false;
00143
00144 if(fscanf(fp,"%d",&val) <= 0) {
00145 DBGA("CalibrationPose::readFromFile - Failed to read joint number");
00146 return;
00147 }
00148
00149 if (val) {
00150 for (j=0; j<mSize; j++) {
00151 if(fscanf(fp,"%f",&floatVal) >= 0) {
00152 DBGA("CalibrationPose::readFromFile - Failed to read joint value");
00153 return;
00154 }
00155
00156 setJointValue(j,floatVal);
00157 }
00158 jointsSet = true;
00159 } else jointsSet = false;
00160
00161
00162
00163 float x,y,z,w;
00164 if(fscanf(fp,"%f %f %f %f",&x, &y, &z, &w)) {
00165 DBGA("CalibrationPose::readFromFile - Failed to read calibration orientation");
00166 return;
00167 }
00168 Quaternion q(w,x,y,z);
00169 if(fscanf(fp,"%f %f %f",&x,&y,&z) <= 0) {
00170 DBGA("CalibrationPose::readFromFile - Failed to read calibration location");
00171 return;
00172 }
00173
00174 vec3 t(x,y,z);
00175 mTransf.set(q,t);
00176 }
00177
00178 void CalibrationPose::writeToFile(FILE *fp)
00179 {
00180 fprintf(fp,"%d\n",getSize());
00181 fprintf(fp,"%f\n",recordedDistance);
00182
00183 if ( sensorsSet ) {
00184 fprintf(fp,"1\n");
00185 for (int i=0; i<getSize(); i++)
00186 fprintf(fp,"%d ",getSensorValue(i));
00187 fprintf(fp,"\n");
00188 } else fprintf(fp,"0\n");
00189 if (mapSet) {
00190 fprintf(fp,"1\n");
00191 for (int i=0; i<getSize(); i++)
00192 fprintf(fp,"%d ",getMap(i) );
00193 fprintf(fp,"\n");
00194 } else fprintf(fp,"0\n");
00195 if (jointsSet) {
00196 fprintf(fp,"1\n");
00197 for (int i=0; i<getSize(); i++)
00198 fprintf(fp,"%f ",getJointValue(i) );
00199 fprintf(fp,"\n");
00200 } else fprintf(fp,"0\n");
00201
00202 fprintf(fp,"%f %f %f %f\n",mTransf.rotation().x, mTransf.rotation().y,
00203 mTransf.rotation().z, mTransf.rotation().w);
00204
00205 fprintf(fp,"%f %f %f\n",mTransf.translation().x(), mTransf.translation().y(),
00206 mTransf.translation().z());
00207 }
00208
00210
00214 void loadPoseListFromFile(std::list<CalibrationPose*> *list, const char *filename)
00215 {
00216 FILE *fp = fopen(filename,"r");
00217 if (!fp) {
00218 fprintf(stderr,"Unable to open calibration file!\n");
00219 return;
00220 }
00221
00222 int nPoses;
00223 CalibrationPose *pose;
00224 if(fscanf(fp,"%d",&nPoses) <= 0) {
00225 DBGA("loadPoseListFromFile - Failed to read number of poses");
00226 return;
00227
00228 }
00229 fprintf(stderr,"Total of %d poses\n",nPoses);
00230 for (int i=0; i<nPoses; i++) {
00231 pose = new CalibrationPose(0);
00232 pose->readFromFile(fp);
00233 list->push_back(pose);
00234 }
00235 fclose(fp);
00236 }
00237
00239
00240 void writePoseListToFile(std::list<CalibrationPose*> *list, const char *filename)
00241 {
00242 FILE *fp = fopen(filename,"w");
00243 if (!fp) {
00244 fprintf(stderr,"Unable to open calibration file!\n");
00245 return;
00246 }
00247 fprintf(fp,"%d\n",list->size());
00248 std::list<CalibrationPose*>::iterator it;
00249 for (it = list->begin(); it!=list->end(); it++) {
00250 (*it)->writeToFile(fp);
00251 }
00252 fprintf(stderr,"Calibration poses saved\n");
00253 fclose(fp);
00254 }
00255
00256 bool CalibrationPose::isSet()
00257 {
00258 return poseSet;
00259 }
00260
00261 void CalibrationPose::setAllJointValues(double *jv)
00262 {
00263 for (int i=0; i<mSize; i++) {
00264 jointValues[i] = jv[i];
00265 }
00266 jointsSet = true;
00267 if (sensorsSet && mapSet) poseSet = true;
00268 }
00269
00270 void CalibrationPose::setJointValue(int j, double jv)
00271 {
00272 jointValues[j] = jv;
00273 jointsSet = true;
00274 }
00275
00276 void CalibrationPose::setAllSensorValues(int *sv)
00277 {
00278 for (int i=0; i<mSize; i++) {
00279 sensorValues[i] = sv[i];
00280 }
00281 sensorsSet = true;
00282 if (jointsSet && mapSet) poseSet = true;
00283 }
00284
00285 void CalibrationPose::setSensorValue(int i, int sv)
00286 {
00287 if (i>=mSize) {
00288 fprintf(stderr,"Error attempting to set calibration pose sensor value\n");
00289 return;
00290 }
00291 sensorValues[i] = sv;
00292 sensorsSet = true;
00293 }
00294
00295 void CalibrationPose::setAllMaps(int *m)
00296 {
00297 for (int i=0; i<mSize; i++) {
00298 sensorMap[i] = m[i];
00299 }
00300 mapSet = true;
00301 if (jointsSet && sensorsSet) poseSet = true;
00302 }
00303
00304 void CalibrationPose::setMap(int i, int mv)
00305 {
00306 if (i>=mSize) {
00307 fprintf(stderr,"Error attempting to set calibration pose map value\n");
00308 return;
00309 }
00310 sensorMap[i] = mv;
00311 mapSet = true;
00312 }
00313
00314
00315
00316 CData::CData(int nd, int ns)
00317 {
00318 nDOF = nd;
00319 nSensors = ns;
00320 slopes = new double[nDOF*nSensors];
00321 intercepts = new double[nDOF];
00322 reset();
00323 }
00324
00325 CData::~CData()
00326 {
00327 delete [] slopes;
00328 delete [] intercepts;
00329 }
00330
00331 void CData::reset()
00332 {
00333 int i;
00334 for (i=0; i<nDOF*nSensors; i++)
00335 slopes[i] = 0;
00336 for (i=0; i<nDOF; i++)
00337 intercepts[i] = 0;
00338 }
00339
00340 void CData::setSlope(int d, int s, double val)
00341 {
00342 if ( d>= nDOF || s >= nSensors) {
00343 fprintf(stderr,"Wrong addressing in Conversion Data\n");
00344 return;
00345 }
00346 slopes[d+s*nDOF] = val;
00347 }
00348
00349 void CData::setIntercept(int d, double val)
00350 {
00351 if ( d >= nDOF ) {
00352 fprintf(stderr,"Wrong addressing in Conversion Data\n");
00353 return;
00354 }
00355 intercepts[d] = val;
00356 }
00357
00358 void CData::addToSlope(int d, int s, double val)
00359 {
00360 if ( d>= nDOF || s >= nSensors) {
00361 fprintf(stderr,"Wrong addressing in Conversion Data\n");
00362 return;
00363 }
00364 slopes[d+s*nDOF] += val;
00365 }
00366
00367 void CData::addToIntercept(int d, double val)
00368 {
00369 if ( d >= nDOF ) {
00370 fprintf(stderr,"Wrong addressing in Conversion Data\n");
00371 return;
00372 }
00373 intercepts[d] += val;
00374 }
00375 double CData::getSlope(int d, int s)
00376 {
00377 if ( d>= nDOF || s >= nSensors) {
00378 fprintf(stderr,"Wrong addressing in Conversion Data\n");
00379 return 0;
00380 }
00381 return slopes[d+s*nDOF];
00382 }
00383
00384 double CData::getIntercept(int d)
00385 {
00386 if ( d >= nDOF ) {
00387 fprintf(stderr,"Wrong addressing in Conversion Data\n");
00388 return 0;
00389 }
00390 return intercepts[d];
00391 }
00392
00393
00394
00395 GloveInterface::GloveInterface(Robot *robot)
00396 {
00397 mRobot = robot;
00398 rawGlove = NULL;
00399
00400 savedDOFVals = new double[mRobot->getNumDOF()];
00401 mRobot->getDOFVals(savedDOFVals);
00402
00403 mData = new CData( mRobot->getNumDOF(), N_SENSOR_VALUES);
00404 currentPose = cPoses.begin();
00405 }
00406
00407 GloveInterface::~GloveInterface()
00408 {
00409 delete mData;
00410 delete [] savedDOFVals;
00411 }
00412
00413 void GloveInterface::setGlove(CyberGlove *glove)
00414 {
00415 rawGlove = glove;
00416 }
00417
00418 void GloveInterface::saveRobotPose()
00419 {
00420 mRobot->getDOFVals(savedDOFVals);
00421 }
00422
00423 void GloveInterface::revertRobotPose()
00424 {
00425 mRobot->forceDOFVals(savedDOFVals);
00426 }
00427
00428 int GloveInterface::instantRead()
00429 {
00430 #ifdef HARDWARE_LIB
00431 if (!rawGlove)
00432 return 0;
00433 if (!rawGlove->instantRead() )
00434 return 0;
00435 return 1;
00436 #else
00437 return 0;
00438 #endif
00439 }
00440
00444 void GloveInterface::setParameters(int s, int d, float sMin, float sMax, float dMin, float dMax)
00445 {
00446 fprintf(stderr,"sensor %d to DOF %d -- sMin %f sMax %f dMin %f dMax %f\n",s,d,sMin,sMax,dMin,dMax);
00447
00448 double slope = ( dMax - dMin ) / ( sMax - sMin );
00449 double intercept = dMin - sMin * slope;
00450 fprintf(stderr," Slope %f and intercept %f \n",slope,intercept);
00451 mData->setSlope(d, s, slope);
00452 mData->setIntercept(d, intercept);
00453 }
00454
00455
00456 void GloveInterface::setParameters(int s, int d, float slope, float intercept)
00457 {
00458 fprintf(stderr,"sensor %d to DOF %d -- slope %f and intercept %f \n", s, d, slope, intercept);
00459 mData->setSlope(d, s, slope);
00460 mData->setIntercept(d, intercept);
00461 }
00462
00463 int GloveInterface::getNumSensors()
00464 {
00465 return N_SENSOR_VALUES;
00466 }
00467
00468 bool GloveInterface::isDOFControlled(int d)
00469 {
00470 for (int s=0; s<N_SENSOR_VALUES; s++)
00471 if ( mData->getSlope(d,s) != 0 )
00472 return true;
00473 return false;
00474 }
00475
00480 float GloveInterface::getDOFValue(int d)
00481 {
00482 #ifdef HARDWARE_LIB
00483 float dofVal = 0;
00484 for ( int s=0; s<N_SENSOR_VALUES; s++) {
00485 int rawValue = rawGlove->getSensorValue ( s );
00486 dofVal += rawValue * mData->getSlope(d,s);
00487 }
00488 dofVal += mData->getIntercept(d);
00489 return dofVal;
00490 #else
00491 assert(0);
00492 d = d;
00493 return 0;
00494 #endif
00495 }
00496
00501 float GloveInterface::getDOFValue(int d, int *rawValues)
00502 {
00503 float dofVal = 0;
00504 for ( int s=0; s<N_SENSOR_VALUES; s++) {
00505 int rawValue = rawValues[s];
00506 dofVal += rawValue * mData->getSlope(d,s);
00507 }
00508 dofVal += mData->getIntercept(d);
00509 return dofVal;
00510 }
00511
00512
00513
00514 void GloveInterface::initCalibration(int type)
00515 {
00516 if ( type == FIST || type == SIMPLE_THUMB || type == ABD_ADD) {
00517
00518 cPoses.clear();
00519 if (type == FIST ) {
00520
00521
00522
00523
00524
00525
00526 int map[] = {-1,-1,-1,-1, 1, 2, 3, 5, 6, 7,-1, 9, 10, 11,-1, 13, 14, 15,-1,-1,-1,-1,-1,-1};
00527 double cp1[] = {0, 0, 0, 0, 0, -6, -4.5, -5.4, 0, 0, 0, -5.6, -3.7, 2, 0, -9.2, -2.0, -4.5, 0, 0, 0, 0, 0, 0};
00528 double cp2[] = {0, 0, 0, 0, 90, 90, 90, 90, 90, 90, 0, 90, 90, 90, 0, 90, 90, 90, 0, 0, 0, 0, 0, 0};
00529 cType = FIST;
00530 cPoses.push_back( new CalibrationPose(N_SENSOR_VALUES, cp1, map));
00531 cPoses.push_back( new CalibrationPose(N_SENSOR_VALUES, cp2, map));
00532 } else if (type == SIMPLE_THUMB) {
00533
00534
00535 int map[] = {16, -1, -1, 17, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1};
00536 double cp1[] = { 70, 0, 0,-50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
00537 double cp2[] = {-10, 0, 0,-50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
00538 cType = SIMPLE_THUMB;
00539 cPoses.push_back( new CalibrationPose(N_SENSOR_VALUES, cp1, map));
00540 cPoses.push_back( new CalibrationPose(N_SENSOR_VALUES, cp2, map));
00541 } else if (type == ABD_ADD) {
00542
00543
00544
00545
00546 int map[] = {-1,-1,-1,-1, -1, -1, -1, -1, -1, -1, 0, -1, -1, -1, 8, -1, -1, -1, 12, -1, -1, -1, -1, -1};
00547 double cp1[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
00548 double cp2[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 0, 0, 0,-20, 0, 0, 0,-30, 0, 0, 0, 0, 0};
00549 cType = ABD_ADD;
00550 cPoses.push_back( new CalibrationPose(N_SENSOR_VALUES, cp1, map));
00551 cPoses.push_back( new CalibrationPose(N_SENSOR_VALUES, cp2, map));
00552 }
00553 } else if (type == COMPLEX_THUMB) {
00554 cType = COMPLEX_THUMB;
00555 } else if (type == MEAN_POSE) {
00556
00557
00558 cType = MEAN_POSE;
00559 cPoses.clear();
00560 }
00561 mCalibrated = false;
00562 currentPose = cPoses.begin();
00563 }
00564
00565 void GloveInterface::nextPose(int direction)
00566 {
00567
00568 if ( cPoses.empty() ) {
00569 fprintf(stderr,"No calibration poses recorded!\n");
00570 return;
00571 }
00572
00573 if (direction > 0) {
00574 currentPose++;
00575 if ( currentPose == cPoses.end() ) currentPose = cPoses.begin();
00576 } else {
00577 if ( currentPose == cPoses.begin() ) currentPose = cPoses.end();
00578 currentPose--;
00579 }
00580 getPoseError();
00581 }
00582
00583
00584 void GloveInterface::showCurrentPose()
00585 {
00586 if ( cPoses.empty() ) {
00587 fprintf(stderr,"No poses recorded!\n");
00588 return;
00589 }
00590
00591 double *desiredVals = new double[mRobot->getNumDOF()];
00592 int *map = (*currentPose)->getAllMaps();
00593 double *jointVals = (*currentPose)->getAllJointValues();
00594 int *sensorVals = (*currentPose)->getAllSensorValues();
00595
00596 int s,d;
00597
00598
00599 for (d=0; d<mRobot->getNumDOF(); d++) {
00600 desiredVals[d] = mRobot->getDOF(d)->getVal();
00601 }
00602
00603
00604 for (s=0; s<(*currentPose)->getSize(); s++) {
00605 d = map[s];
00606 if ( d >= 0) {
00607 if ( (*currentPose)->jointsSet )
00608 desiredVals[d] = jointVals[s];
00609 else if ( (*currentPose)->sensorsSet)
00610 desiredVals[d] = getDOFValue(d, sensorVals) ;
00611 else fprintf(stderr,"Can not show pose - neither joints nor sensors are set!\n");
00612
00613 }
00614 }
00615 mRobot->forceDOFVals(desiredVals);
00616 transf t = mRobot->getFlockTran()->getAbsolute( (*currentPose)->getTransf() );
00617
00618 mRobot->setTran( t );
00619 }
00620
00621 void GloveInterface::recordPoseFromGlove(int d)
00622 {
00623 #ifdef HARDWARE_LIB
00624 if (!instantRead()) {
00625 fprintf(stderr,"Can not read glove for calibration\n");
00626 return;
00627 }
00628
00629 int sv[N_SENSOR_VALUES];
00630 double* jv = new double[mRobot->getNumDOF()];
00631
00632 for (int i=0; i<N_SENSOR_VALUES; i++) {
00633 sv[i] = rawGlove->getSensorValue(i);
00634 }
00635
00636 if (cType==FIST || cType==SIMPLE_THUMB || cType == ABD_ADD) {
00637 if ( cPoses.empty() ) {
00638 fprintf(stderr,"No poses recorded!\n");
00639 return;
00640 }
00641 (*currentPose)->setAllSensorValues(sv);
00642 } else if (cType == COMPLEX_THUMB) {
00643 cPoses.push_back( new CalibrationPose(N_SENSOR_VALUES) );
00644 currentPose = cPoses.end();
00645 currentPose--;
00646
00647 (*currentPose)->setAllSensorValues(sv);
00648
00649 int map[] = {16, 18, 19, 17, 1, 2, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1};
00650 (*currentPose)->setAllMaps(map);
00651 (*currentPose)->recordedDistance = d;
00652 fprintf(stderr,"Distance: %d\n",d);
00653 } else if (cType == MEAN_POSE) {
00654 cPoses.push_back( new CalibrationPose(N_SENSOR_VALUES) );
00655 currentPose = cPoses.end();
00656 currentPose--;
00657 (*currentPose)->setAllSensorValues(sv);
00658 for (int d=0; d<mRobot->getNumDOF(); d++) {
00659 jv[d] = getDOFValue(d,sv);
00660 mRobot->checkSetDOFVals(jv);
00661 }
00662 (*currentPose)->setAllJointValues(jv);
00663 int map[] = {0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,-1,-1,-1,-1};
00664 (*currentPose)->setAllMaps(map);
00665
00666
00667 transf t = mRobot->getFlockTran()->getMount() * mRobot->getTran();
00668
00669 (*currentPose)->setTransf(t);
00670
00671 fprintf(stderr,"Pose for mean recorded!\n");
00672 } else {
00673 fprintf(stderr,"No calibration type initialized!\n");
00674 }
00675 delete [] jv;
00676 #else
00677 d = d;
00678 assert(0);
00679 #endif
00680 }
00681
00682 bool GloveInterface::poseSet()
00683 {
00684 if ( cPoses.empty() )
00685 return false;
00686
00687 return (*currentPose)->isSet();
00688 }
00689
00690
00691 bool GloveInterface::readyToCalibrate()
00692 {
00693 if (cType == FIST || cType == SIMPLE_THUMB || cType == ABD_ADD) {
00694 int numSet = 0;
00695 std::list<CalibrationPose*>::iterator it;
00696 for (it=cPoses.begin(); it!=cPoses.end(); it++) {
00697 if ( (*it)->isSet() ) numSet++;
00698 }
00699 if (numSet>=2) return true;
00700 } else if (cType == COMPLEX_THUMB) {
00701 if ( (int)cPoses.size() > 5 )return true;
00702 } else if (cType == MEAN_POSE) {
00703 if (!cPoses.empty()) return true;
00704 }
00705 return false;
00706 }
00707
00708 bool GloveInterface::performCalibration()
00709 {
00710 switch (cType) {
00711 case FIST:
00712 return performSimpleCalibration();
00713 break;
00714 case ABD_ADD:
00715 return performSimpleCalibration();
00716 break;
00717 case SIMPLE_THUMB:
00718 return performThumbCalibration();
00719 break;
00720 case COMPLEX_THUMB:
00721 performComplexCalibration();
00722 mCalibrated = true;
00723
00724 return true;
00725 break;
00726 case MEAN_POSE:
00727 computeMeanPose();
00728 break;
00729 default:
00730 fprintf(stderr,"Unknown calibration type requested\n");
00731 break;
00732 }
00733 return false;
00734 }
00735
00736
00737
00738 bool GloveInterface::performSimpleCalibration()
00739 {
00740 if (!readyToCalibrate() ){
00741 return false;
00742 }
00743
00744 CalibrationPose *cp1, *cp2;
00745 std::list<CalibrationPose*>::iterator it;
00746 it = cPoses.begin();
00747 cp1 = (*it);
00748 it++;
00749 cp2 = (*it);
00750
00751 float sMin, sMax, dMin, dMax;
00752 for (int i=0; i<N_SENSOR_VALUES;i++){
00753
00754 if ( cp1->getMap(i) < 0 || cp2->getMap(i) < 0 ){
00755 fprintf(stderr,"Sensor %d masked\n",i);
00756 continue;
00757 }
00758 int d = cp1->getMap(i);
00759 if ( d != cp2->getMap(i) ) {
00760 fprintf(stderr,"Error! Sensor %d has different maps in poses!\n",i);
00761 continue;
00762 }
00763 sMin = cp1->getSensorValue(i); sMax = cp2->getSensorValue(i);
00764 dMin = cp1->getJointValue(i); dMax = cp2->getJointValue(i);
00765 setParameters(i, d, sMin, sMax, dMin, dMax);
00766 }
00767
00768 mCalibrated = true;
00769 return true;
00770 }
00771
00772 bool GloveInterface::performThumbCalibration()
00773 {
00774 if (!readyToCalibrate() ){
00775 return false;
00776 }
00777
00778 CalibrationPose *cp1, *cp2;
00779 std::list<CalibrationPose*>::iterator it;
00780 it = cPoses.begin();
00781 cp1 = (*it);
00782 it++;
00783 cp2 = (*it);
00784
00785 int R11 = cp1->getSensorValue(3);
00786 int R12 = cp2->getSensorValue(3);
00787
00788 double S1 = mData->getSlope(17, 3);
00789 double alpha = S1 * ( R11 - R12 );
00790
00791 int R21 = cp1->getSensorValue(0);
00792 int R22 = cp2->getSensorValue(0);
00793
00794 double S2 = alpha / ( R22 - R21 );
00795 double I2 = - S2 * R21;
00796
00797 mData->setSlope(17, 0, S2);
00798 mData->setIntercept(17, mData->getIntercept(17)+I2);
00799 fprintf(stderr,"Result: slope %f and intercept %f \n",S2,I2);
00800
00801 mCalibrated = true;
00802 return true;
00803 }
00804
00805 bool GloveInterface::performComplexCalibration()
00806 {
00807 for (int i=0; i<100; i++) {
00808 complexCalibrationStep();
00809 }
00810 return true;
00811 }
00812
00813 bool GloveInterface::complexCalibrationStep()
00814 {
00815
00816 int i;
00817
00818 int nPoses = 0;
00819 for (currentPose = cPoses.begin(); currentPose!=cPoses.end(); currentPose++) {
00820 showCurrentPose();
00821
00822
00823 if ( getPoseError() > -7.8)
00824 nPoses ++;
00825 }
00826 double *JD = new double[nPoses * 30];
00827 int ldd = nPoses * 3;
00828
00829 double *P = new double[nPoses * 3];
00830 double *fg = new double[10];
00831
00832 i=0;
00833 for (currentPose = cPoses.begin(); currentPose!=cPoses.end(); currentPose++) {
00834 showCurrentPose();
00835 if (getPoseError() <= -7.8)
00836 continue;
00837 assembleJMatrix( JD + i*3, ldd);
00838 assemblePMatrix( P + i*3 );
00839 i++;
00840 }
00841
00842
00843
00844
00845
00846
00847
00848
00849
00850
00851
00852
00853
00854
00855
00856
00857
00858
00859
00860
00861 int info,rank;
00862 int lwork = 100 * 3 * nPoses;
00863 double *work = new double[lwork];
00864 double *SVDs = new double[MIN(3*nPoses,10)];
00865
00866 dgelss(3*nPoses, 10, 1,
00867 JD, 3*nPoses, P, 3*nPoses, SVDs, 1.0e-5, &rank, work, lwork, &info);
00868
00869
00870
00871
00872
00873
00874
00875
00876 mData->addToIntercept(16,P[0]);
00877 mData->addToIntercept(17,P[1]);
00878 mData->addToIntercept(18,P[2]);
00879 mData->addToIntercept(19,P[3]);
00880
00881 mData->addToSlope(16,0,P[4]);
00882 mData->addToSlope(16,3,P[5]);
00883 mData->addToSlope(17,0,P[6]);
00884 mData->addToSlope(17,3,P[7]);
00885 mData->addToSlope(18,1,P[8]);
00886 mData->addToSlope(19,2,P[9]);
00887
00888 fprintf(stderr,"Total error AFTER step: %f\n",getTotalError());
00889 currentPose = cPoses.begin();
00890
00891 delete [] SVDs;
00892 delete [] work;
00893 delete [] JD;
00894 delete [] P;
00895 delete [] fg;
00896
00897 return true;
00898 }
00899
00900 bool
00901 GloveInterface::computeMeanPose()
00902 {
00903
00904 double *jv = new double[mRobot->getNumDOF()];
00905
00906 for (int d=0; d<mRobot->getNumDOF(); d++) {
00907 jv[d]=0;
00908 }
00909
00910 for (currentPose = cPoses.begin(); currentPose != cPoses.end(); currentPose++) {
00911 for (int d=0; d<mRobot->getNumDOF(); d++) {
00912 jv[d] += (*currentPose)->getJointValue(d);
00913 }
00914 }
00915
00916 for (int d=0; d<mRobot->getNumDOF(); d++) {
00917 jv[d] = jv[d] / cPoses.size();
00918 }
00919
00920 cPoses.push_back( new CalibrationPose(N_SENSOR_VALUES) );
00921 currentPose = cPoses.end();
00922 currentPose--;
00923 (*currentPose)->setAllJointValues(jv);
00924 int map[] = {0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,-1,-1,-1,-1};
00925 (*currentPose)->setAllMaps(map);
00926 showCurrentPose();
00927
00928 FILE *fp = fopen("mean_pose.txt","w");
00929 fprintf(stderr,"Mean pose written to mean_pose.txt \n");
00930 (*currentPose)->writeToFile(fp);
00931 fclose(fp);
00932
00933 delete [] jv;
00934 return true;
00935 }
00936
00937 void GloveInterface::saveCalibration(const char* filename)
00938 {
00939 FILE *fp = fopen(filename,"w");
00940 if (!fp) {
00941 fprintf(stderr,"Unable to open calibration file!\n");
00942 return;
00943 }
00944
00945 int d,s;
00946 fprintf(fp,"%d %d\n",mRobot->getNumDOF(), N_SENSOR_VALUES);
00947 for (d=0; d<mRobot->getNumDOF(); d++) {
00948 for (s=0; s<N_SENSOR_VALUES; s++)
00949 fprintf(fp, "%f ",mData->getSlope(d,s));
00950 fprintf(fp,"\n");
00951 }
00952 for (d=0; d<mRobot->getNumDOF(); d++)
00953 fprintf(fp,"%f ",mData->getIntercept(d));
00954 fprintf(fp,"\n");
00955 fclose(fp);
00956 fprintf(stderr,"Calibration saved\n");
00957 }
00958
00959 bool GloveInterface::loadCalibration(const char* filename)
00960 {
00961 FILE *fp = fopen(filename,"r");
00962 if (!fp) {
00963 fprintf(stderr,"Unable to open calibration file!\n");
00964 return false;
00965 }
00966
00967 int d,s;
00968 int numDOF, numSens;
00969 float val;
00970
00971 if (fscanf(fp,"%d %d ",&numDOF,&numSens) <= 0) {
00972 DBGA("GloveInterface::loadCalibration - Failed to dof num or sensor num");
00973 return false;
00974 }
00975
00976 if ( numDOF != mRobot->getNumDOF() || numSens != N_SENSOR_VALUES ) {
00977 fprintf(stderr,"WARNING: calibration file contains wrong number of DOFs/sensors\n");
00978 return false;
00979 }
00980
00981 mData->reset();
00982 for (d=0; d<numDOF; d++) {
00983 for (s=0; s<numSens; s++) {
00984 if(fscanf(fp,"%f",&val) <= 0) {
00985 DBGA("GloveInterface::loadCalibration - Failed to dof or sensor value");
00986 return false;
00987 }
00988 }
00989 mData->setSlope(d,s,val);
00990 }
00991
00992 for (d=0; d<mRobot->getNumDOF(); d++) {
00993 if(fscanf(fp,"%f",&val) ){
00994 DBGA("GloveInterface::loadCalibration - Failed to dof num or sensor num");
00995 return false;
00996 }
00997 mData->setIntercept(d,val);
00998 }
00999
01000 fclose(fp);
01001 fprintf(stderr,"Calibration loaded from file\n");
01002 return true;
01003 }
01004
01005
01006 void GloveInterface::saveCalibrationPoses(const char *filename)
01007 {
01008 writePoseListToFile(&cPoses, filename);
01009 currentPose = cPoses.begin();
01010 }
01011
01012 void GloveInterface::loadCalibrationPoses(const char *filename)
01013 {
01014 loadPoseListFromFile(&cPoses, filename);
01015 currentPose = cPoses.begin();
01016 }
01017
01018 double GloveInterface::getPoseError(vec3* error, position* thumbLocation)
01019 {
01020 double shellDistance = 8;
01021 double cFactor = (*currentPose)->recordedDistance;
01022
01023 vec3 expectedVector, measuredVector, e;
01024
01025 showCurrentPose();
01026 Body *thumbTip = mRobot->getChain(4)->getLink(2);
01027 Body *indexTip = mRobot->getChain(0)->getLink(2);
01028 position p1, p2;
01029 double rawDistance;
01030 rawDistance = mRobot->getWorld()->getDist(thumbTip, indexTip, p1, p2);
01031
01032 if (thumbLocation != NULL) {
01033 *thumbLocation = p1;
01034 }
01035
01036 p1 = p1 * thumbTip->getTran() * mRobot->getChain(4)->getTran().inverse();
01037 p2 = p2 * indexTip->getTran() * mRobot->getChain(4)->getTran().inverse();
01038 measuredVector = p2 - p1;
01039
01040 expectedVector = normalise(measuredVector);
01041 expectedVector = ( cFactor + shellDistance) * expectedVector;
01042
01043
01044
01045 e = measuredVector - expectedVector;
01046
01047 if (error != NULL) {
01048 *error = e;
01049 }
01050
01051
01052
01053
01054
01055 return e.len();
01056 }
01057
01058 double GloveInterface::getTotalError()
01059 {
01060 double totalError = 0;
01061 for ( currentPose=cPoses.begin(); currentPose!=cPoses.end(); currentPose++) {
01062 totalError += getPoseError();
01063 }
01064 totalError /= cPoses.size();
01065 return totalError;
01066 }
01067
01068 void GloveInterface::getPoseJacobian(double *J)
01069 {
01070 double t1 = mRobot->getDOF(16)->getVal();
01071 double t2 = mRobot->getDOF(17)->getVal() + 0.8639;
01072 double t3 = mRobot->getDOF(18)->getVal() + 0.0873;
01073 double t4 = mRobot->getDOF(19)->getVal() + 1.4835;
01074
01075 jacobian(t1, t2, t3, t4, 0, 0, 1000, J);
01076 }
01077
01078 void GloveInterface::assembleJMatrix(double *D, int ldd)
01079 {
01080 double t1 = mRobot->getDOF(16)->getVal();
01081 double t2 = mRobot->getDOF(17)->getVal() + 0.8639;
01082 double t3 = mRobot->getDOF(18)->getVal() + 0.0873;
01083 double t4 = mRobot->getDOF(19)->getVal() + 1.4835;
01084
01085 position errorPos;
01086 getPoseError(NULL,&errorPos);
01087
01088 double J[12];
01089
01090 jacobian(t1, t2, t3, t4, errorPos.x(), errorPos.y(), errorPos.z(), J);
01091
01092 double s0 = (*currentPose)->getSensorValue(0);
01093 double s1 = (*currentPose)->getSensorValue(3);
01094 double s2 = (*currentPose)->getSensorValue(1);
01095 double s3 = (*currentPose)->getSensorValue(2);
01096
01097 double dTdG[4*6];
01098 compute_dTdG(s0, s1, s2, s3, dTdG);
01099
01100 double JD[3*6];
01101 dgemm("N", "N", 3, 6, 4,
01102 1, J, 3,
01103 dTdG, 4,
01104 0, JD, 3);
01105
01106 int i,j;
01107 for (i=0; i<3; i++) {
01108 for (j=0; j<4; j++) {
01109 D[ i + j*ldd] = J[ i + 3*j];
01110 }
01111 }
01112 for (i=0; i<3; i++) {
01113 for (j=0; j<6; j++) {
01114 D[ i + (4+j)*ldd ] = JD[ i + 3*j ];
01115 }
01116 }
01117 }
01118
01119 void GloveInterface::assemblePMatrix( double *P )
01120 {
01121 vec3 error;
01122 getPoseError(&error);
01123
01124 P[0] = error.x();
01125 P[1] = error.y();
01126 P[2] = error.z();
01127 }
01128
01129 void GloveInterface::clearPoses()
01130 {
01131 cPoses.clear();
01132 currentPose = cPoses.begin();
01133 }
01134
01135 void GloveInterface::startGlove()
01136 {
01137 DBGA("Disabled... Init glove from World menu");
01138 }