gloveServer_impl.h
Go to the documentation of this file.
1 
18 #ifndef GLOVESERVER_H
19 #define GLOVESERVER_H
20 
21 /* system includes */
22 #include <string>
23 #include <vector>
24 #include <boost/thread.hpp>
25 
26 /* ros */
27 #include <ros/ros.h>
28 #include <sstream>
29 
30 #include <asr_msgs/AsrGlove.h>
31 
32 /* my includes */
33 #include "gloveDevice.h"
34 
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); }
37 
38 #define DEFAULT_CALIBRATION_PATH "../calibrationData/"
39 
40 typedef enum
41 {
43 } gloveID;
44 typedef enum
45 {
47 } noteType;
48 
50 {
51 public:
52  gloveServer_impl(gloveID id, std::string name);
53  bool init(std::string serialPort);
54  bool loadCalibFile(const char *srcFileName);
56 
57  void start();
58  void stop();
59  void join();
60 
64  void workerThread();
66  boost::thread * boostWorkerThread;
67 
68 private:
69 
71  std::string myName;
72  char* serialID;
74  unsigned int GLOVERAW_MAP2_GLOVEINVENTOR[22];
75 
76  /* Ros */
80 
83  std::vector<double> FulcRaw1;
84  std::vector<double> FulcRad1;
85 
86  std::vector<double> FulcRaw2;
87  std::vector<double> FulcRad2;
88 
89  double getRadian(int index, unsigned char val);
90  double *getRadianArray(unsigned char* data, unsigned int size);
91 
93  bool permuteValues(unsigned char* valIn, unsigned char* valOut);
94 
95  // ----- Notification Thread ----- //
97  bool sendNotificationDataToRos(double* data, unsigned int size, asr_msgs::AsrGlove gloveData, ros::Publisher publisher);
98 
99 };
100 
101 #endif /* GLOVESERVER_H */
unsigned int GLOVERAW_MAP2_GLOVEINVENTOR[22]
double getRadian(int index, unsigned char val)
boost::thread * boostWorkerThread
Thread for delivering tracker data to nCenter.
gloveDevice * gloveDev
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
std::string myName
ros::Publisher gloveDataPub
bool threadRunning
flag switching on/off thread
gloveServer_impl(gloveID id, std::string name)
noteType
ros::NodeHandle rosNode
bool sendNotificationDataToRos(double *data, unsigned int size, asr_msgs::AsrGlove gloveData, ros::Publisher publisher)
Send sensor data to Notification Center.
gloveID
std::vector< double > FulcRad1


asr_cyberglove_lib
Author(s): Heller Florian, Meißner Pascal, Nguyen Trung, Yi Xie
autogenerated on Mon Jun 10 2019 12:40:38