00001 
00017 
00018 
00019 
00020 
00021 #include <stdio.h>
00022 #include <error.h>
00023 #include <stdio.h>
00024 #include <unistd.h>
00025 
00026 #include <termios.h>
00027 #include <fcntl.h>
00028 #include <stdio.h>
00029 #include <unistd.h>
00030 #include <sys/ioctl.h>
00031 #include <errno.h>
00032 #include <sys/types.h>
00033 #include <sys/stat.h>
00034 #include <signal.h>
00035 #include <string.h>
00036 #include <pwd.h>
00037 #include <sys/time.h>
00038 
00039 #include "cyberglove/serial_glove.h"
00040 
00041 int VERBOSE=0;
00042 
00043 FILE * serial;
00044 
00045 static float values[GLOVE_SIZE];
00046 
00047  
00048 float glove_positions[GLOVE_SIZE];
00049 
00050 int gloveButtonValue=0;
00051 
00052 int glove_start_reads=0, glove_reads=0;
00053 
00054 char glove_message[100];
00055 
00056 
00057 struct termios termios_save;
00058 static int serial_port_fd = -1;
00059 
00060 void open_board(char *port) {
00061   struct termios termios_p;
00062 
00063   serial_port_fd = open(port, O_RDWR | O_NOCTTY); 
00064 
00065   if (serial_port_fd < 0) error(1, errno, "can't open serial port! maybe run as root...");
00066 
00068   tcgetattr(serial_port_fd, &termios_p);
00069 
00070   
00071   
00072 
00073   termios_p.c_cflag = B115200;
00074   termios_p.c_cflag |= CS8;
00075   termios_p.c_cflag |= CREAD;
00076   termios_p.c_iflag = IGNPAR | IGNBRK;
00077   termios_p.c_cflag |= CLOCAL;
00078   termios_p.c_oflag = 0;
00079   termios_p.c_lflag = 0; 
00080   termios_p.c_cc[VTIME] = 1; 
00081   termios_p.c_cc[VMIN] = 0;  
00082 
00083 
00084 
00085   memcpy(&termios_save, &termios_p, sizeof(struct termios));
00086   
00088   tcsetattr(serial_port_fd, TCSANOW, &termios_p);
00089   tcflush(serial_port_fd, TCOFLUSH);  
00090   tcflush(serial_port_fd, TCIFLUSH);
00091 
00092   
00093   
00094 
00095   sleep(1);
00096 }
00097 
00098 
00099 
00100 
00101 
00106 int read_stepping(int fd, unsigned char *b, int n) {
00107   int i=0;
00108   
00109   int res=0;
00110   int remain;
00111   
00112   remain = n;
00113 
00114   do {
00115     res=read(fd, &b[i], remain);
00116     if (res>0) { 
00117       remain -= res;
00118       i += res;
00119     };
00120 
00121     if (res<0) { error(1, errno, "readg!"); };
00122     if (res==0) {
00123       strcpy(glove_message, "(glove read failed, is it connected?)");
00124       
00125       
00126       tcsetattr(serial_port_fd, TCSANOW, &termios_save);
00127       return 1;
00128     };
00129 
00130     if (remain) usleep (remain * 500); 
00131   } while (  remain);
00132 
00133   return (remain!=0);
00134 }
00135 
00136 void  writeg(int fd, char *b, int n) {
00137   int i;
00138   for (i=0;i<n;i++) {
00139     write(fd, &b[i], 1);
00140   };
00141   
00142 }
00143 
00144 
00145 void read_values(float *dest) {
00146  restart:
00147   glove_start_reads++;
00148   tcflush(serial_port_fd, TCIFLUSH);
00149   tcflush(serial_port_fd, TCOFLUSH);
00150   writeg(serial_port_fd, "G", 1);
00151   int i;
00152   unsigned char ch[GLOVE_SIZE+2]={0}; 
00153 
00154   usleep(GLOVE_SIZE*10);
00155   
00156   
00157   if (read_stepping(serial_port_fd, &ch, GLOVE_SIZE+2)) {
00158     
00159     goto restart;
00160   };
00161   
00162 
00163   if (ch[0]!='G') {
00164     
00165     
00166     goto restart; 
00167   };
00168 
00170   for (i=0; i<GLOVE_SIZE; i++) {
00171     if (ch[i+1]==0) { 
00172       
00173       goto restart;
00174     };
00175   };
00176 
00177   for (i=0; i<GLOVE_SIZE; i++) {
00178     dest[i] = (ch[i+1]-1.0)/254.0;
00179   }
00180 
00181 
00182   strcpy(glove_message, "");  
00183   glove_reads++;
00184 }
00185 
00186 
00187 int read_button_value() {
00188  restartButtonRead:
00189   tcflush(serial_port_fd, TCIFLUSH);
00190   tcflush(serial_port_fd, TCOFLUSH);
00191   writeg(serial_port_fd, "?W", 2);
00192   unsigned char ch[3]={0};    
00193 
00194   
00195   usleep(GLOVE_SIZE*10);
00196 
00197   if (read_stepping(serial_port_fd, &ch, 3)) {
00198     goto restartButtonRead;
00199   };
00200 
00201   return ch[2];
00202 }
00203 
00204 
00205 int setup_glove(const char* path_to_glove)
00206  {
00207   open_board(path_to_glove);
00208 
00209   int i;
00210   for (i=0;i<GLOVE_SIZE;i++) 
00211     {
00212       values[i]=0.0;
00213       glove_positions[i] = 0.0;
00214     }
00215   
00216   return 0;
00217  }
00218 
00219 
00220 
00221 
00222  
00223 
00224 
00226 float* glove_get_values() {
00227   read_values(values);
00228 
00229   int i;
00230   for (i=0; i<GLOVE_SIZE; i++)
00231     glove_positions[i] = values[i];
00232 
00233   return glove_positions;
00234 }
00235 
00236