gloveServer_impl.h
Go to the documentation of this file.
00001 
00018 #ifndef GLOVESERVER_H
00019 #define GLOVESERVER_H
00020 
00021 /* system includes */
00022 #include <string>
00023 #include <vector>
00024 #include <boost/thread.hpp>
00025 
00026 /* ros */
00027 #include <ros/ros.h>
00028 #include <sstream>
00029 
00030 #include <asr_msgs/AsrGlove.h>
00031 
00032 /* my includes */
00033 #include "gloveDevice.h"
00034 
00035 #define DIEonERR(value) if (value<0) { \
00036  fprintf(stderr,"%i DIED in %s line %i with error %i\n",getpid(),__FILE__,__LINE__,-value);exit(1); }
00037 
00038 #define DEFAULT_CALIBRATION_PATH "../calibrationData/"
00039 
00040 typedef enum
00041 {
00042         rightGlove = 1, leftGlove
00043 } gloveID;
00044 typedef enum
00045 {
00046         VALUE, RADIAN
00047 } noteType;
00048 
00049 class gloveServer_impl
00050 {
00051 public:
00052         gloveServer_impl(gloveID id, std::string name);
00053         bool init(std::string serialPort);
00054         bool loadCalibFile(const char *srcFileName);
00055         ~gloveServer_impl();
00056 
00057         void start();
00058         void stop();
00059         void join();
00060 
00062         bool threadRunning;
00064         void workerThread();
00066         boost::thread * boostWorkerThread;
00067 
00068 private:
00069 
00070         gloveID myID;
00071         std::string myName;
00072         char* serialID;
00073         gloveDevice *gloveDev;
00074         unsigned int GLOVERAW_MAP2_GLOVEINVENTOR[22];
00075 
00076         /* Ros */
00077         ros::NodeHandle rosNode;
00078         ros::Publisher gloveDataPub;
00079         ros::Publisher gloveDataPub_radian;
00080 
00083         std::vector<double> FulcRaw1;
00084         std::vector<double> FulcRad1;
00085 
00086         std::vector<double> FulcRaw2;
00087         std::vector<double> FulcRad2;
00088 
00089         double getRadian(int index, unsigned char val);
00090         double *getRadianArray(unsigned char* data, unsigned int size);
00091 
00093         bool permuteValues(unsigned char* valIn, unsigned char* valOut);
00094 
00095         // ----- Notification Thread ----- //
00097     bool sendNotificationDataToRos(double* data, unsigned int size, asr_msgs::AsrGlove gloveData, ros::Publisher publisher);
00098 
00099 };
00100 
00101 #endif /* GLOVESERVER_H */


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