GloveInterface Class Reference

Interface between a GraspIt robot and the CyberGlove. More...

#include <gloveInterface.h>

List of all members.

Public Types

enum  calibrationTypes {
  FIST, SIMPLE_THUMB, COMPLEX_THUMB, ABD_ADD,
  MEAN_POSE
}
 

The types of calibrations available with this interface.

More...

Public Member Functions

void assembleJMatrix (double *D, int lda)
void assemblePMatrix (double *P)
bool calibrated ()
void clearPoses ()
float getDOFValue (int d)
 Uses the latest sensor values from the CyberGlove and computes the values of a particular DOF.
int getNumPoses ()
int getNumSensors ()
 Returns the number of raw sensors in the CyberGlove.
double getPoseError (vec3 *error=NULL, position *thumbLocation=NULL)
void getPoseJacobian (double *J)
RobotgetRobot ()
double getTotalError ()
 GloveInterface (Robot *robot)
void initCalibration (int type)
int instantRead ()
 Asks the raw CyberGlove to refresh its readings from the sensors via the serial port.
bool isDOFControlled (int d)
 Tells wether a particular robot DOF is controlled via the CyberGlove or not.
bool loadCalibration (const char *filename)
void loadCalibrationPoses (const char *filename)
void nextPose (int direction)
bool performCalibration ()
bool poseSet ()
bool readyToCalibrate ()
void recordPoseFromGlove (int d=0)
void revertRobotPose ()
void saveCalibration (const char *filename)
void saveCalibrationPoses (const char *filename)
void saveRobotPose ()
void setGlove (CyberGlove *glove)
void setParameters (int s, int d, float slope, float intercept)
 Sets the parametes for linear conversion for a particular combination of raw sensor and dof number.
void setParameters (int s, int d, float sMin, float sMax, float dMin, float dMax)
 Computes parametes for linear conversion for a particular combination of raw sensor and dof number.
void showCurrentPose ()
void startGlove ()
 Initializes the glove, in case we want to use it during the calibration.
 ~GloveInterface ()

Private Member Functions

bool complexCalibrationStep ()
bool computeMeanPose ()
float getDOFValue (int d, int *rawValues)
 Main interface function, gets a dof value from a list of raw sensor readings.
bool performComplexCalibration ()
bool performSimpleCalibration ()
bool performThumbCalibration ()

Private Attributes

std::list< CalibrationPose * > cPoses
 A list of poses currently used for calibration.
int cType
 The type of calibration currently being performed.
std::list< CalibrationPose * >
::iterator 
currentPose
 The current pose selected (for recording data or for display).
bool mCalibrated
 Whether this interface is calibrated (and ready to use) or not.
CDatamData
 The data for performing linear conversion from raw sensor data to dof values.
RobotmRobot
 The robot that uses this interface.
CyberGlove * rawGlove
 The instance of the raw glove where raw sensor values come from.
double * savedDOFVals

Detailed Description

Interface between a GraspIt robot and the CyberGlove.

This class interfaces a Robot with a CyberGlove. The Raw Cyber Glove (in the Sensors library) just talks to the serial port and gets raw glove sensor values between 1 and 255. This interface converts them to joint angle values, can perform calibration to compute the parameters for this conversion, and matches glove sensor numbers to robot DOF numbers.

This class can also calibrate the CyberGlove (compute the conversion parameters from raw sensor data to dof values). Unfortunately, the calibrations are rather poorly engineered from a software standpoint, they should really have a dedicated interface and inheritance hierarchies.

Up to some degree, all calibrations behave the same way: the user must supply a set of postures that are expected to match a pre-defined set of joint angles. Alternatively, the calibration postures can also be read from a file. After the record step, the calibration step uses these postures to compute the parameters. This step depends on the calibration type. See the enum calibrationType for details.

The most difficult to calibrate is the thumb, where a couple of glove sensors are affected by more then one dof. See the paper by Griffin, Findley, Turner and Cutkosky, "Calibration and Mapping of a Human Hand for Dexterous Telemanipulation" for some details that have inspired the calibration done here.

Definition at line 156 of file gloveInterface.h.


Member Enumeration Documentation

The types of calibrations available with this interface.

Here is what each does:

FIST: asks the user for only two poses: with the hand flat and with the fist closed. Then, uses the two resulting values for each finger flexion dof to compute the slope and intercept. Does NOT calibrate the thumb at all, or the abduction / adduction dofs.

SIMPLE_THUMB:

COMPLEX_THUMB: asks the user to record as many poses as pssible where the distance between the index finger and the thumb is known. This is done either by touching the index and the thumb, or by holding between them an object of know size. Then attempts to use this data to calibrate the thumb sensors.

ABD_ADD: asks for two poses, at the two ends of abd / add to compute the linear parameters for those dofs.

MEAN_POSE: not really a calibration; the user records as many poses as she want, then this computes the mean of those poses.

Enumerator:
FIST 
SIMPLE_THUMB 
COMPLEX_THUMB 
ABD_ADD 
MEAN_POSE 

Definition at line 232 of file gloveInterface.h.


Constructor & Destructor Documentation

GloveInterface::GloveInterface ( Robot robot  ) 

Definition at line 354 of file gloveInterface.cpp.

GloveInterface::~GloveInterface (  ) 

Definition at line 366 of file gloveInterface.cpp.


Member Function Documentation

void GloveInterface::assembleJMatrix ( double *  D,
int  lda 
)

Definition at line 1026 of file gloveInterface.cpp.

void GloveInterface::assemblePMatrix ( double *  P  ) 

Definition at line 1067 of file gloveInterface.cpp.

bool GloveInterface::calibrated (  )  [inline]

Definition at line 240 of file gloveInterface.h.

void GloveInterface::clearPoses (  ) 

Definition at line 1077 of file gloveInterface.cpp.

bool GloveInterface::complexCalibrationStep (  )  [private]

Definition at line 772 of file gloveInterface.cpp.

bool GloveInterface::computeMeanPose (  )  [private]

Definition at line 860 of file gloveInterface.cpp.

float GloveInterface::getDOFValue ( int  d  ) 

Uses the latest sensor values from the CyberGlove and computes the values of a particular DOF.

Asks the glove for the value of all sensors, then uses them to convert to a dof value. In general, the value of the dof d is obtained by: dof_d = intercepts_d + sum_over_all_sensors_s[slope(s,d) * raw_sensor(s)]

Definition at line 439 of file gloveInterface.cpp.

float GloveInterface::getDOFValue ( int  d,
int *  rawValues 
) [private]

Main interface function, gets a dof value from a list of raw sensor readings.

Sort of ugly code... This does the exact same as getDOFValue(int), but assuming raw values are not actually read from the cyberglove but passed as a parameter.

Definition at line 460 of file gloveInterface.cpp.

int GloveInterface::getNumPoses (  )  [inline]

Definition at line 245 of file gloveInterface.h.

int GloveInterface::getNumSensors (  ) 

Returns the number of raw sensors in the CyberGlove.

Definition at line 422 of file gloveInterface.cpp.

double GloveInterface::getPoseError ( vec3 error = NULL,
position thumbLocation = NULL 
)

Definition at line 966 of file gloveInterface.cpp.

void GloveInterface::getPoseJacobian ( double *  J  ) 

Definition at line 1016 of file gloveInterface.cpp.

Robot* GloveInterface::getRobot (  )  [inline]

Definition at line 187 of file gloveInterface.h.

double GloveInterface::getTotalError (  ) 

Definition at line 1006 of file gloveInterface.cpp.

void GloveInterface::initCalibration ( int  type  ) 

Definition at line 473 of file gloveInterface.cpp.

int GloveInterface::instantRead (  ) 

Asks the raw CyberGlove to refresh its readings from the sensors via the serial port.

Definition at line 387 of file gloveInterface.cpp.

bool GloveInterface::isDOFControlled ( int  d  ) 

Tells wether a particular robot DOF is controlled via the CyberGlove or not.

Definition at line 427 of file gloveInterface.cpp.

bool GloveInterface::loadCalibration ( const char *  filename  ) 

Definition at line 918 of file gloveInterface.cpp.

void GloveInterface::loadCalibrationPoses ( const char *  filename  ) 

Definition at line 960 of file gloveInterface.cpp.

void GloveInterface::nextPose ( int  direction  ) 

Definition at line 524 of file gloveInterface.cpp.

bool GloveInterface::performCalibration (  ) 

Definition at line 667 of file gloveInterface.cpp.

bool GloveInterface::performComplexCalibration (  )  [private]

Definition at line 764 of file gloveInterface.cpp.

bool GloveInterface::performSimpleCalibration (  )  [private]

Definition at line 697 of file gloveInterface.cpp.

bool GloveInterface::performThumbCalibration (  )  [private]

Definition at line 731 of file gloveInterface.cpp.

bool GloveInterface::poseSet (  ) 

Definition at line 641 of file gloveInterface.cpp.

bool GloveInterface::readyToCalibrate (  ) 

Definition at line 650 of file gloveInterface.cpp.

void GloveInterface::recordPoseFromGlove ( int  d = 0  ) 

Definition at line 580 of file gloveInterface.cpp.

void GloveInterface::revertRobotPose (  ) 

Definition at line 382 of file gloveInterface.cpp.

void GloveInterface::saveCalibration ( const char *  filename  ) 

Definition at line 896 of file gloveInterface.cpp.

void GloveInterface::saveCalibrationPoses ( const char *  filename  ) 

Definition at line 954 of file gloveInterface.cpp.

void GloveInterface::saveRobotPose (  ) 

Definition at line 377 of file gloveInterface.cpp.

void GloveInterface::setGlove ( CyberGlove *  glove  ) 

Definition at line 372 of file gloveInterface.cpp.

void GloveInterface::setParameters ( int  s,
int  d,
float  slope,
float  intercept 
)

Sets the parametes for linear conversion for a particular combination of raw sensor and dof number.

Definition at line 415 of file gloveInterface.cpp.

void GloveInterface::setParameters ( int  s,
int  d,
float  sMin,
float  sMax,
float  dMin,
float  dMax 
)

Computes parametes for linear conversion for a particular combination of raw sensor and dof number.

Sets the calibration paramteres given a min-max range for a sensor as well as the DOF it governs. Should soon be private.

Definition at line 403 of file gloveInterface.cpp.

void GloveInterface::showCurrentPose (  ) 

Definition at line 543 of file gloveInterface.cpp.

void GloveInterface::startGlove (  ) 

Initializes the glove, in case we want to use it during the calibration.

We can also use pre-recorded poses if we don't want to.

Definition at line 1083 of file gloveInterface.cpp.


Member Data Documentation

std::list<CalibrationPose*> GloveInterface::cPoses [private]

A list of poses currently used for calibration.

Definition at line 166 of file gloveInterface.h.

int GloveInterface::cType [private]

The type of calibration currently being performed.

Definition at line 170 of file gloveInterface.h.

std::list<CalibrationPose*>::iterator GloveInterface::currentPose [private]

The current pose selected (for recording data or for display).

Definition at line 168 of file gloveInterface.h.

Whether this interface is calibrated (and ready to use) or not.

Definition at line 172 of file gloveInterface.h.

The data for performing linear conversion from raw sensor data to dof values.

Definition at line 163 of file gloveInterface.h.

The robot that uses this interface.

Definition at line 161 of file gloveInterface.h.

CyberGlove* GloveInterface::rawGlove [private]

The instance of the raw glove where raw sensor values come from.

Definition at line 159 of file gloveInterface.h.

double* GloveInterface::savedDOFVals [private]

Definition at line 174 of file gloveInterface.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


graspit
Author(s):
autogenerated on Wed Jan 25 11:00:21 2012