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 #ifndef _GLOVEINTERFACE_H_
00027 #define _GLOVEINTERFACE_H_
00028
00029 class vec3;
00030 class position;
00031 class CyberGlove;
00032 class Robot;
00033
00034 #include <QString>
00035 #include <list>
00036 #include <vector>
00037
00038 #include "matvec3D.h"
00039
00041
00045 class CalibrationPose {
00046 private:
00048 int mSize;
00050 double *jointValues;
00052 int *sensorValues;
00054
00056 int *sensorMap;
00058 transf mTransf;
00060 void init(int size);
00061 public:
00062 CalibrationPose(int size);
00063 CalibrationPose(int size, double *joints, int *map);
00064 ~CalibrationPose();
00065
00066 void setJointValue(int j, double jv);
00067 void setAllJointValues(double *jv);
00068 void setSensorValue(int i, int sv);
00069 void setAllSensorValues(int *sv);
00070 void setMap(int i, int mv);
00071 void setAllMaps(int *m);
00072 void setTransf(transf t){mTransf = t;}
00073
00074 double getJointValue(int i){return jointValues[i];}
00075 double *getAllJointValues(){return jointValues;}
00076 int getSensorValue(int i){return sensorValues[i];}
00077 int *getAllSensorValues(){return sensorValues;}
00078 int getMap(int i){return sensorMap[i];}
00079 int *getAllMaps(){return sensorMap;}
00080 transf getTransf(){return mTransf;}
00081
00083 bool isSet();
00084 int getSize(){return mSize;}
00085 bool jointsSet, sensorsSet, mapSet, poseSet;
00086
00088 double recordedDistance;
00089
00091 QString miscInfo;
00092
00093 void writeToFile(FILE *fp);
00094 void readFromFile(FILE *fp);
00095 };
00096
00098
00113 class CData {
00114 private:
00115 double *slopes,*intercepts;
00116 int nDOF, nSensors;
00117 public:
00118 CData(int nd, int ns);
00119 ~CData();
00120 double getSlope(int d, int s);
00121 double getIntercept(int d);
00122 void setSlope(int d, int s, double val);
00123 void setIntercept(int d, double val);
00124 void addToSlope(int d, int s, double val);
00125 void addToIntercept(int d, double val);
00126 void reset();
00127 };
00128
00130
00156 class GloveInterface {
00157 private:
00159 CyberGlove *rawGlove;
00161 Robot *mRobot;
00163 CData *mData;
00164
00166 std::list<CalibrationPose*> cPoses;
00168 std::list<CalibrationPose*>::iterator currentPose;
00170 int cType;
00172 bool mCalibrated;
00173
00174 double *savedDOFVals;
00175
00176 bool computeMeanPose();
00177 bool performSimpleCalibration();
00178 bool performThumbCalibration();
00179 bool performComplexCalibration();
00180 bool complexCalibrationStep();
00181
00183 float getDOFValue(int d, int *rawValues);
00184 public:
00185 GloveInterface(Robot *robot);
00186 ~GloveInterface();
00187 Robot* getRobot(){return mRobot;}
00188 void setGlove(CyberGlove *glove);
00189
00191
00192 void startGlove();
00194 int instantRead();
00195
00197 bool isDOFControlled(int d);
00199 float getDOFValue(int d);
00200
00202 int getNumSensors();
00204 void setParameters(int s, int d, float sMin, float sMax, float dMin, float dMax);
00206 void setParameters(int s, int d, float slope, float intercept);
00207
00208
00209
00211
00232 enum calibrationTypes{FIST, SIMPLE_THUMB, COMPLEX_THUMB, ABD_ADD, MEAN_POSE};
00233
00234 void nextPose(int direction);
00235 void showCurrentPose();
00236 void recordPoseFromGlove(int d=0);
00237
00238 bool poseSet();
00239 bool readyToCalibrate();
00240 bool calibrated(){return mCalibrated;}
00241
00242 void saveCalibrationPoses(const char* filename);
00243 void loadCalibrationPoses(const char* filename);
00244 void clearPoses();
00245 int getNumPoses(){return cPoses.size();}
00246
00247 bool loadCalibration(const char* filename);
00248 void saveCalibration(const char* filename);
00249
00250 void initCalibration(int type);
00251 bool performCalibration();
00252
00253 double getPoseError(vec3* error=NULL, position* thumbLocation=NULL);
00254 double getTotalError();
00255 void getPoseJacobian(double *J);
00256 void assembleJMatrix(double *D, int lda);
00257 void assemblePMatrix( double *P );
00258
00259 void saveRobotPose();
00260 void revertRobotPose();
00261 };
00262 #endif