24 #include <boost/thread.hpp> 30 #include <asr_msgs/AsrGlove.h> 35 #define DIEonERR(value) if (value<0) { \ 36 fprintf(stderr,"%i DIED in %s line %i with error %i\n",getpid(),__FILE__,__LINE__,-value);exit(1); } 38 #define DEFAULT_CALIBRATION_PATH "../calibrationData/" 53 bool init(std::string serialPort);
89 double getRadian(
int index,
unsigned char val);
93 bool permuteValues(
unsigned char* valIn,
unsigned char* valOut);
unsigned int GLOVERAW_MAP2_GLOVEINVENTOR[22]
double getRadian(int index, unsigned char val)
boost::thread * boostWorkerThread
Thread for delivering tracker data to nCenter.
double * getRadianArray(unsigned char *data, unsigned int size)
std::vector< double > FulcRaw2
bool loadCalibFile(const char *srcFileName)
std::vector< double > FulcRad2
bool permuteValues(unsigned char *valIn, unsigned char *valOut)
permute sensor values according to GLOVERAW_MAP2_GLOVEINVENTOR mapping
ros::Publisher gloveDataPub_radian
bool init(std::string serialPort)
void workerThread()
this method is called by static method s_workerthread
std::vector< double > FulcRaw1
ros::Publisher gloveDataPub
bool threadRunning
flag switching on/off thread
gloveServer_impl(gloveID id, std::string name)
bool sendNotificationDataToRos(double *data, unsigned int size, asr_msgs::AsrGlove gloveData, ros::Publisher publisher)
Send sensor data to Notification Center.
std::vector< double > FulcRad1