gloveDevice.h
Go to the documentation of this file.
00001 
00018 #ifndef GLOVEDEVICE_H
00019 #define GLOVEDEVICE_H
00020 
00021 /* system includes */
00022 #include <pthread.h>
00023 
00024 /* my includes */
00025 #include "gloveTypes.h"
00026 #include "gloveStatus.h"
00027 #include "serial.h"
00028 
00036 #define CR 13
00037 #define LF 10
00038 #define MAX_SENSORS 22
00039 
00040 class gloveDevice
00041 {
00042 public:
00043         gloveDevice();
00044         ~gloveDevice();
00045 
00046         bool init(const char *serialDev);
00047         void stop();
00048 
00049         /* Display status */
00050         void showCurrentStatus();
00051 
00052         /* Sensors: init */
00053 
00054         //M
00055         bool cmdSetSwSensorMask(sensorMask_t mask);
00056         bool cmdGetSwSensorMask(sensorMask_t *mask);
00057         //K
00058         bool cmdGetHwSensorMask(sensorMask_t *mask);
00059         //N
00060         bool cmdSetNbSensorsEnabled(uchar_t n);
00061         bool cmdGetNbSensorsEnabled(uchar_t *n);
00062         //S
00063         bool cmdGetNbSensorsTotal(uchar_t *n);
00064         //T
00065         bool cmdSetSamplePeriod(samplePeriod_t period);
00066         bool cmdGetSamplePeriod(samplePeriod_t *period);
00067 
00068         /* Sensors: switches */
00069 
00070         //D
00071         bool cmdSetTimeStamp(bool enable);
00072         bool cmdGetTimeStamp(bool *enable);
00073         //U
00074         bool cmdSetGloveStatus(bool enable);
00075         bool cmdGetGloveStatus(bool *enable);
00076 
00077         /* Sensors: values */
00078 
00079         //G
00080         bool cmdGetSensorValues(vector_t values, uchar_t *n, statusQuery_t *query,
00081                         gloveStatusByte_t *gloveStatusByte);
00082         //Y
00083         bool cmdGetSensorValuesSync(vector_t values, uchar_t *n, bool *errorSync,
00084                         gloveStatusByte_t *gloveStatusByte);
00085         //S
00086         bool cmdSetStreamValues(bool enable);
00087 
00088         bool cmdGetSensorDummyValues(vector_t values, uchar_t *n,
00089                         statusQuery_t *query, gloveStatusByte_t *gloveStatusByte);
00090 
00091         /* Sensors: calibrate  */
00092 
00093         //A
00094         bool cmdSetActuate(int n, vector_t index, vector_t values);
00095         bool cmdSetActuateAll(vector_t values);
00096         bool cmdGetActuateAll(vector_t values);
00097         //C
00098         bool cmdSetCalibrateAll(vector_t offset, vector_t gain);
00099         bool cmdSetCalibrateOffset(uchar_t index, uchar_t offset);
00100         bool cmdSetCalibrateGain(uchar_t index, uchar_t gain);
00101         bool cmdGetCalibrateAll(vector_t offset, vector_t gain);
00102 
00103         /* Glove: information */
00104 
00105         //B
00106         bool cmdSetBaudRate(uchar_t baudDivide);
00107         bool cmdGetBaudRate(uchar_t *baudDivide);
00108         //P
00109         bool cmdSetParameterFlags(parameterFlags_t flags);
00110         bool cmdGetParameterFlags(parameterFlags_t *flags);
00111         //G
00112         bool cmdGetConnectStatus(statusConnect_t *status);
00113         //R
00114         bool cmdGetHand(bool *rightHand);
00115         //V
00116         bool cmdGetGloveVersion(gloveVersion_t *version);
00117         //Y
00118         bool cmdSetBinarySync(bool enable);
00119         bool cmdGetBinarySync(bool *enable);
00120 
00121         /* Glove: switches */
00122 
00123         //F
00124         bool cmdSetDigitalFilter(bool enable);
00125         bool cmdGetDigitalFilter(bool *enable);
00126         //J
00127         bool cmdSetControlLight(bool enable);
00128         bool cmdGetControlLight(bool *enable);
00129         //L
00130         bool cmdSetWristLight(bool enable);
00131         bool cmdGetWristLight(bool *enable);
00132         //Q
00133         bool cmdSetQuantized(bool enable);
00134         bool cmdGetQuantized(bool *enable);
00135         //W
00136         bool cmdSetWristToggle(bool enable);
00137         bool cmdGetWristToggle(bool *enable);
00138 
00139         /* Glove: internal commands */
00140 
00141         //^I
00142         bool cmdReinitializeCyberGlove();
00143         //^R
00144         bool cmdRestartFirmware();
00145 
00146 private:
00147         gloveStatus status;
00148         SerialDevice serial;int serialId;
00149         bool error;
00150         pthread_mutex_t serial_lock;
00151 
00152         void lock_serial();
00153         void unlock_serial();
00154 
00155         uchar_t getChar();
00156         void getString(vector_t s, int n);
00157         void sendChar(uchar_t);
00158         void sendString(vector_t s, int n);
00159 
00160         bool readResponseSet(uchar_t c);
00161         bool readResponseSet(uchar_t c1, uchar_t c2);
00162         bool readNullChar();
00163         bool readResponseGet(uchar_t c);
00164 
00165         bool cmdSetChar(uchar_t name, uchar_t val);
00166         bool cmdGetChar(uchar_t name, uchar_t *val);
00167         bool cmdGetBool(uchar_t name, bool *val);
00168 
00169         bool internalCmd(uchar_t cmd);
00170 
00171 };
00172 
00173 #endif /* GLOVEDEVICE_H */


asr_cyberglove_lib
Author(s): Heller Florian, Meißner Pascal, Nguyen Trung, Yi Xie
autogenerated on Thu Jun 6 2019 22:02:33