00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #include <stdlib.h>
00030 #include <string.h>
00031 #include <termios.h>
00032 #include <unistd.h>
00033 #include <fcntl.h>
00034 #include <sys/ioctl.h>
00035 #include <sys/types.h>
00036 #include <sys/stat.h>
00037
00038 #include <time.h>
00039 #include <sys/time.h>
00040
00041 #include <sched.h>
00042 #include <pthread.h>
00043
00044 #include "geniePi.h"
00045
00046 #ifndef TRUE
00047 # define TRUE (1==1)
00048 # define FALSE (1==0)
00049 #endif
00050
00051
00052
00053
00054 #define MAX_GENIE_REPLYS 16
00055
00056 static struct genieReplyStruct genieReplys [MAX_GENIE_REPLYS] ;
00057 static int genieReplysHead = 0 ;
00058 static int genieReplysTail = 0 ;
00059
00060 #ifdef GENIE_DEBUG
00061 int genieAck = FALSE ;
00062 int genieNak = FALSE ;
00063 int genieChecksumErrors = 0 ;
00064 int genieTimeouts = 0 ;
00065 #else
00066 static int genieAck = FALSE ;
00067 static int genieNak = FALSE ;
00068 static int genieChecksumErrors = 0 ;
00069 static int genieTimeouts = 0 ;
00070 #endif
00071
00072 static pthread_mutex_t genieMutex ;
00073
00074 static int genieFd = -1;
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084 static int genieOpen (char *device, int baud)
00085 {
00086 struct termios options ;
00087 speed_t myBaud ;
00088 int status, fd ;
00089
00090 switch (baud)
00091 {
00092 case 50: myBaud = B50 ; break ;
00093 case 75: myBaud = B75 ; break ;
00094 case 110: myBaud = B110 ; break ;
00095 case 134: myBaud = B134 ; break ;
00096 case 150: myBaud = B150 ; break ;
00097 case 200: myBaud = B200 ; break ;
00098 case 300: myBaud = B300 ; break ;
00099 case 600: myBaud = B600 ; break ;
00100 case 1200: myBaud = B1200 ; break ;
00101 case 1800: myBaud = B1800 ; break ;
00102 case 2400: myBaud = B2400 ; break ;
00103 case 9600: myBaud = B9600 ; break ;
00104 case 19200: myBaud = B19200 ; break ;
00105 case 38400: myBaud = B38400 ; break ;
00106 case 57600: myBaud = B57600 ; break ;
00107 case 115200: myBaud = B115200 ; break ;
00108 case 230400: myBaud = B230400 ; break ;
00109
00110 default:
00111 return -2 ;
00112 }
00113
00114 if ((fd = open (device, O_RDWR | O_NOCTTY | O_NDELAY | O_NONBLOCK)) == -1)
00115 return -1 ;
00116
00117 fcntl (fd, F_SETFL, O_RDWR) ;
00118
00119
00120
00121 tcgetattr (fd, &options) ;
00122
00123 cfmakeraw (&options) ;
00124 cfsetispeed (&options, myBaud) ;
00125 cfsetospeed (&options, myBaud) ;
00126
00127 options.c_cflag |= (CLOCAL | CREAD) ;
00128 options.c_cflag &= ~PARENB ;
00129 options.c_cflag &= ~CSTOPB ;
00130 options.c_cflag &= ~CSIZE ;
00131 options.c_cflag |= CS8 ;
00132 options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG) ;
00133 options.c_oflag &= ~OPOST ;
00134
00135 options.c_cc [VMIN] = 0 ;
00136 options.c_cc [VTIME] = 100 ;
00137
00138 tcsetattr (fd, TCSANOW | TCSAFLUSH, &options) ;
00139
00140 ioctl (fd, TIOCMGET, &status);
00141
00142 status |= TIOCM_DTR ;
00143 status |= TIOCM_RTS ;
00144
00145 ioctl (fd, TIOCMSET, &status);
00146
00147 usleep (10000) ;
00148
00149 return fd ;
00150 }
00151
00152
00153
00154
00155
00156
00157
00158
00159 static void genieFlush (int fd)
00160 {
00161 tcflush (fd, TCIOFLUSH) ;
00162 }
00163
00164
00165
00166
00167
00168
00169
00170
00171 void genieClose (void)
00172 {
00173 close (genieFd) ;
00174 }
00175
00176
00177
00178
00179
00180
00181
00182
00183 static int genieDataAvail (int fd)
00184 {
00185 int result ;
00186
00187 if (ioctl (fd, FIONREAD, &result) == -1)
00188 return -1 ;
00189
00190 return result ;
00191 }
00192
00193
00194
00195
00196
00197
00198
00199 static unsigned long long epoch ;
00200
00201 static unsigned int millis (void)
00202 {
00203 struct timeval tv ;
00204 unsigned long long t1 ;
00205
00206 gettimeofday (&tv, NULL) ;
00207
00208 t1 = (tv.tv_sec * 1000000 + tv.tv_usec) / 1000 ;
00209
00210 return (unsigned int)(t1 - epoch) ;
00211 }
00212
00213 static void delay (unsigned int howLong)
00214 {
00215 struct timespec sleeper, dummy ;
00216
00217 sleeper.tv_sec = (time_t)(howLong / 1000) ;
00218 sleeper.tv_nsec = (long)(howLong % 1000) * 1000000 ;
00219
00220 nanosleep (&sleeper, &dummy) ;
00221 }
00222
00223 static void delayMicroseconds (unsigned int howLong)
00224 {
00225 struct timespec sleeper, dummy ;
00226
00227 sleeper.tv_sec = 0 ;
00228 sleeper.tv_nsec = (long)(howLong * 1000) ;
00229
00230 nanosleep (&sleeper, &dummy) ;
00231 }
00232
00233
00234
00235
00236
00237
00238
00239
00240
00241 static int genieGetchar (void)
00242 {
00243 unsigned int timeUp = millis () + 5 ;
00244 unsigned char x ;
00245
00246 while (millis () < timeUp)
00247 if (genieDataAvail (genieFd))
00248 {
00249 if (read (genieFd, &x, 1) == 1)
00250 return ((int)x) & 0xFF ;
00251 return -1 ;
00252 }
00253 else
00254 delayMicroseconds (101) ;
00255
00256 return -1 ;
00257 }
00258
00259
00260
00261
00262
00263
00264
00265
00266 static void geniePutchar (int data)
00267 {
00268 unsigned char c = (unsigned char)data ;
00269 write (genieFd, &c, 1) ;
00270 }
00271
00272
00273
00274
00275
00276
00277
00278
00279
00280 static void *genieReplyListener (void *data)
00281 {
00282 struct sched_param sched ;
00283 int pri = 20 ;
00284
00285 unsigned int cmd, object, index, msb, lsb, csum ;
00286 struct genieReplyStruct *reply ;
00287 int next ;
00288
00289
00290
00291
00292 memset (&sched, 0, sizeof(sched)) ;
00293
00294 if (pri > sched_get_priority_max (SCHED_RR))
00295 pri = sched_get_priority_max (SCHED_RR) ;
00296
00297 sched.sched_priority = pri ;
00298 sched_setscheduler (0, SCHED_RR, &sched) ;
00299
00300
00301
00302 while (genieFd == -1)
00303 delay (1) ;
00304
00305
00306
00307 for (;;)
00308 {
00309 while ((cmd = genieGetchar ()) == -1)
00310 ;
00311
00312 if (cmd == GENIE_ACK)
00313 { genieAck = TRUE ; continue ; }
00314 if (cmd == GENIE_NAK)
00315 { genieNak = TRUE ; continue ; }
00316
00317 csum = cmd ;
00318
00319 if ((object = genieGetchar ()) == -1) { ++genieTimeouts ; continue ; } ; csum ^= object ;
00320 if ((index = genieGetchar ()) == -1) { ++genieTimeouts ; continue ; } ; csum ^= index ;
00321 if ((msb = genieGetchar ()) == -1) { ++genieTimeouts ; continue ; } ; csum ^= msb ;
00322 if ((lsb = genieGetchar ()) == -1) { ++genieTimeouts ; continue ; } ; csum ^= lsb ;
00323
00324 if (genieGetchar () != csum)
00325 {
00326 ++genieChecksumErrors ;
00327 continue ;
00328 }
00329
00330
00331
00332 next = (genieReplysHead + 1) & (MAX_GENIE_REPLYS - 1) ;
00333 if (next != genieReplysTail)
00334 {
00335 reply = &genieReplys [genieReplysHead] ;
00336 reply->cmd = cmd ;
00337 reply->object = object ;
00338 reply->index = index ;
00339 reply->data = msb << 8 | lsb ;
00340 genieReplysHead = next ;
00341 }
00342 }
00343
00344 return (void *)NULL ;
00345 }
00346
00347
00348
00349
00350
00351
00352
00353
00354 int genieReplyAvail (void)
00355 {
00356 return (genieReplysHead != genieReplysTail) ;
00357 }
00358
00359
00360
00361
00362
00363
00364
00365
00366
00367 void genieGetReply (struct genieReplyStruct *reply)
00368 {
00369 while (!genieReplyAvail ())
00370 delay (1) ;
00371
00372 memcpy (reply, &genieReplys [genieReplysTail], sizeof (struct genieReplyStruct)) ;
00373
00374 genieReplysTail = (genieReplysTail + 1) & (MAX_GENIE_REPLYS - 1) ;
00375 }
00376
00377
00378
00379
00380
00381
00382
00383
00384 static int _genieReadObj (int object, int index)
00385 {
00386 struct genieReplyStruct reply ;
00387 unsigned int timeUp, checksum ;
00388
00389
00390
00391
00392 while (genieReplyAvail ())
00393 genieGetReply (&reply) ;
00394
00395 genieAck = genieNak = FALSE ;
00396
00397 geniePutchar (GENIE_READ_OBJ) ; checksum = GENIE_READ_OBJ ;
00398 geniePutchar (object) ; checksum ^= object ;
00399 geniePutchar (index) ; checksum ^= index ;
00400 geniePutchar (checksum) ;
00401
00402
00403
00404
00405 for (timeUp = millis () + 50 ; millis () < timeUp ;)
00406 {
00407 if (genieNak)
00408 return -1 ;
00409
00410 if (genieReplyAvail ())
00411 {
00412 genieGetReply (&reply) ;
00413 if ((reply.cmd == GENIE_REPORT_OBJ) && (reply.object == object) && (reply.index == index))
00414 return reply.data ;
00415 }
00416
00417 delayMicroseconds (101) ;
00418 }
00419
00420 return -1 ;
00421 }
00422
00423 int genieReadObj (int object, int index)
00424 {
00425 int result ;
00426
00427 pthread_mutex_lock (&genieMutex) ;
00428 result = _genieReadObj (object, index) ;
00429 pthread_mutex_unlock (&genieMutex) ;
00430
00431 return result ;
00432
00433 }
00434
00435
00436
00437
00438
00439
00440
00441
00442 static int _genieWriteObj (int object, int index, unsigned int data)
00443 {
00444 unsigned int checksum, msb, lsb ;
00445
00446 lsb = (data >> 0) & 0xFF ;
00447 msb = (data >> 8) & 0xFF ;
00448
00449 genieAck = genieNak = FALSE ;
00450
00451 geniePutchar (GENIE_WRITE_OBJ) ; checksum = GENIE_WRITE_OBJ ;
00452 geniePutchar (object) ; checksum ^= object ;
00453 geniePutchar (index) ; checksum ^= index ;
00454 geniePutchar (msb) ; checksum ^= msb ;
00455 geniePutchar (lsb) ; checksum ^= lsb ;
00456 geniePutchar (checksum) ;
00457
00458
00459
00460
00461 while ((genieAck == FALSE) && (genieNak == FALSE))
00462 delay (1) ;
00463
00464 return 0 ;
00465 }
00466
00467 int genieWriteObj (int object, int index, unsigned int data)
00468 {
00469 int result ;
00470
00471 pthread_mutex_lock (&genieMutex) ;
00472 result = _genieWriteObj (object, index, data) ;
00473 pthread_mutex_unlock (&genieMutex) ;
00474
00475 return result ;
00476 }
00477
00478
00479
00480
00481
00482
00483
00484
00485 static int _genieWriteContrast (int value)
00486 {
00487 unsigned int checksum ;
00488
00489 genieAck = genieNak = FALSE ;
00490
00491 geniePutchar (GENIE_WRITE_CONTRAST) ; checksum = GENIE_WRITE_CONTRAST ;
00492 geniePutchar (value) ; checksum ^= value ;
00493 geniePutchar (checksum) ;
00494
00495
00496
00497
00498 while ((genieAck == FALSE) && (genieNak == FALSE))
00499 delay (1) ;
00500
00501 return 0 ;
00502 }
00503
00504 int genieWriteContrast (int value)
00505 {
00506 int result ;
00507
00508 pthread_mutex_lock (&genieMutex) ;
00509 result = _genieWriteContrast (value) ;
00510 pthread_mutex_unlock (&genieMutex) ;
00511
00512 return result ;
00513 }
00514
00515
00516
00517
00518
00519
00520
00521
00522
00523 static int _genieWriteStr (int index, char *string)
00524 {
00525 char *p ;
00526 unsigned int checksum ;
00527 int len = strlen (string) ;
00528
00529 if (len > 255)
00530 return -1 ;
00531
00532 genieAck = genieNak = FALSE ;
00533
00534 geniePutchar (GENIE_WRITE_STR) ; checksum = GENIE_WRITE_STR ;
00535 geniePutchar (index) ; checksum ^= index ;
00536 geniePutchar ((unsigned char)len) ; checksum ^= len ;
00537 for (p = string ; *p ; ++p)
00538 {
00539 geniePutchar (*p) ;
00540 checksum ^= *p ;
00541 }
00542 geniePutchar (checksum) ;
00543
00544
00545
00546
00547 while ((genieAck == FALSE) && (genieNak == FALSE))
00548 delay (1) ;
00549
00550 return 0 ;
00551 }
00552
00553 static int _genieWriteStrU (int index, char *string)
00554 {
00555 char *p ;
00556 unsigned int checksum ;
00557 int len = strlen (string) ;
00558
00559 if (len > 255)
00560 return -1 ;
00561
00562 genieAck = genieNak = FALSE ;
00563
00564 geniePutchar (GENIE_WRITE_STRU) ; checksum = GENIE_WRITE_STRU ;
00565 geniePutchar (index) ; checksum ^= index ;
00566 geniePutchar ((unsigned char)len) ; checksum ^= len ;
00567 for (p = string ; *p ; ++p)
00568 {
00569 geniePutchar (*p) ;
00570 checksum ^= *p ;
00571 }
00572 geniePutchar (checksum) ;
00573
00574
00575
00576
00577 while ((genieAck == FALSE) && (genieNak == FALSE))
00578 delay (1) ;
00579
00580 return 0 ;
00581 }
00582
00583
00584 int genieWriteStr (int index, char *string)
00585 {
00586 int result ;
00587
00588 pthread_mutex_lock (&genieMutex) ;
00589 result = _genieWriteStr (index, string) ;
00590 pthread_mutex_unlock (&genieMutex) ;
00591
00592 return result ;
00593 }
00594
00595 int genieWriteStrU (int index, char *string)
00596 {
00597 int result ;
00598
00599 pthread_mutex_lock (&genieMutex) ;
00600 result = _genieWriteStrU (index, string) ;
00601 pthread_mutex_unlock (&genieMutex) ;
00602
00603 return result ;
00604 }
00605
00606
00607
00608
00609
00610
00611
00612
00613 static int _genieSetPin (int mode, int pin)
00614 {
00615 struct genieReplyStruct reply ;
00616 unsigned int timeUp, checksum ;
00617
00618
00619
00620
00621 while (genieReplyAvail ())
00622 genieGetReply (&reply) ;
00623
00624 geniePutchar (0xFF);
00625 geniePutchar (0x90);
00626 geniePutchar (0x00) ;
00627 geniePutchar (mode) ;
00628 geniePutchar (pin) ;
00629
00630
00631 return -1 ;
00632 }
00633
00634 int genieSetPin (int mode, int pin)
00635 {
00636 int result ;
00637
00638 pthread_mutex_lock (&genieMutex) ;
00639 result = _genieSetPin (mode, pin) ;
00640 pthread_mutex_unlock (&genieMutex) ;
00641
00642 return result ;
00643
00644 }
00645
00646
00647
00648
00649
00650
00651
00652
00653
00654
00655 int genieSetup (char *device, int baud)
00656 {
00657 int i ;
00658
00659 pthread_t myThread ;
00660 struct timeval tv ;
00661
00662 if ((genieFd = genieOpen (device, baud)) < 0)
00663 return -1 ;
00664
00665 genieFlush (genieFd) ;
00666
00667 gettimeofday (&tv, NULL) ;
00668 epoch = (tv.tv_sec * 1000000 + tv.tv_usec) / 1000 ;
00669
00670
00671
00672
00673
00674
00675 for (i = 0 ; i < 10 ; ++i)
00676 {
00677 geniePutchar ('X') ;
00678 if (genieGetchar () == GENIE_NAK)
00679 break ;
00680 }
00681
00682 return pthread_create (&myThread, NULL, genieReplyListener, NULL) ;
00683 }