amtec_io.c
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, Robert Bosch LLC.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Robert Bosch nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *********************************************************************/
00036  
00037 #include <stdio.h>
00038 #include <stdlib.h>
00039 #include <math.h>
00040 
00041 #include <termios.h>
00042 #include <unistd.h>
00043 #include <fcntl.h>
00044 #include <errno.h>
00045 #include <string.h>
00046 #include <sys/types.h>
00047 #include <sys/stat.h>
00048 #include <sys/ioctl.h>
00049 #include <sys/time.h>
00050 #include <linux/serial.h>
00051 
00052 #include "amtec_io.h"
00053 
00054 
00055 //#define IO_DEBUG
00056 
00057 int getAttrParity( enum PARITY_TYPE par )
00058 {
00059   if( par == N ) // No parity
00060   {
00061     return IGNPAR;
00062   }
00063   else
00064   {
00065     return INPCK;
00066   }
00067 }
00068     
00069 int getAttrSWFlowControl( int flowcontrol )
00070 {
00071   if( flowcontrol )
00072   {
00073     return IXON;
00074   }
00075   else
00076   {
00077     return IXOFF;
00078   }
00079 }
00080         
00081 int getAttrBitsPerByte(size_t bits_per_byte )
00082 {
00083   switch( bits_per_byte )
00084   {
00085   case 5:
00086     return CS5;
00087   case 6:
00088     return CS6;
00089   case 7:
00090     return CS7;
00091   case 8:
00092   default:
00093     return CS8;
00094   }
00095 }
00096             
00097 int getAttrStopBits(int stop_bits)
00098 {
00099   if( stop_bits == 2 )
00100   {
00101     return CSTOPB;
00102   }
00103   else
00104   {
00105     return 0;
00106   }
00107 }
00108                 
00109 int getAttrFlowControl( int flowcontrol )
00110 {
00111   if( flowcontrol )
00112   {
00113     return CRTSCTS;
00114   }
00115   else
00116   {
00117     return CLOCAL;
00118   }
00119 }
00120                     
00121 int getAttrParityType(enum PARITY_TYPE par)
00122 {
00123   if( par == N) // No parity
00124   {
00125     return 0;
00126   }
00127 
00128   if( par == O) // Odd parity
00129   {
00130     return ( PARENB | PARODD );
00131   }
00132   else // Even parity
00133   {
00134     return PARENB;
00135   }
00136 }
00137                         
00138 int getAttrBaudRate(int baud_rate)
00139 {
00140   switch( baud_rate ) 
00141   {
00142   case 4800:
00143     return B4800;
00144   case 9600:
00145     return B9600;
00146 #ifdef B14400
00147   case 14400:
00148     return B14400;
00149 #endif
00150   case 19200:
00151     return B19200;
00152 #ifdef B28800
00153   case 28800:
00154     return B28800;
00155 #endif
00156   case 38400:
00157     return B38400;
00158   case 57600:
00159     return B57600;
00160   case 115200:
00161     return B115200;
00162   default:
00163     return B9600;
00164   }
00165 }
00166                             
00167 long bytesWaiting(int sd)
00168 {
00169   long available = 0;
00170   if (ioctl(sd, FIONREAD, &available) == 0)
00171     return available;
00172   else
00173     return -1;
00174 }
00175                                   
00176 void amtecDeviceSetParams(amtec_powercube_device_p dev)
00177 {
00178   struct termios ctio;
00179                                       
00180   tcgetattr(dev->fd, &ctio); /* save current port settings */
00181                                         
00182   ctio.c_iflag = getAttrSWFlowControl( dev->swf )
00183                | getAttrParity( dev->parity );
00184   ctio.c_oflag = 0;
00185   ctio.c_cflag = CREAD
00186                | getAttrFlowControl( dev->hwf || dev->swf )
00187                | getAttrParityType( dev->parity )
00188                | getAttrBitsPerByte( dev->databits )
00189                | getAttrStopBits( dev->stopbits );
00190   ctio.c_lflag = 0;
00191   ctio.c_cc[VTIME] = 0; /* inter-character timer unused */
00192   ctio.c_cc[VMIN] = 0; /* blocking read until 0 chars received */
00193                                                     
00194   cfsetispeed(&ctio, (speed_t) getAttrBaudRate(dev->baud));
00195   cfsetospeed(&ctio, (speed_t) getAttrBaudRate(dev->baud));
00196                                                         
00197   tcflush(dev->fd, TCIFLUSH);
00198   tcsetattr(dev->fd, TCSANOW, &ctio);
00199 }
00200                                                             
00201 void amtecDeviceSetBaudrate(amtec_powercube_device_p dev, int baud_rate)
00202 {
00203   struct termios ctio;
00204                                                                 
00205   tcgetattr(dev->fd, &ctio); /* save current port settings */
00206                                                                   
00207   cfsetispeed(&ctio, (speed_t) getAttrBaudRate(baud_rate));
00208   cfsetospeed(&ctio, (speed_t) getAttrBaudRate(baud_rate));
00209                                                                       
00210   tcflush(dev->fd, TCIFLUSH);
00211   tcsetattr(dev->fd, TCSANOW, &ctio);
00212 }
00213                                                                           
00214 int amtecDeviceConnectPort(amtec_powercube_device_p dev)
00215 {
00216   fprintf(stderr, "\nset device:\n");
00217   fprintf(stderr, "   port   = %s\n", dev->ttyport);
00218   fprintf(stderr, "   baud   = %d\n", dev->baud);
00219   fprintf(stderr, "   params = %d%s%d\n", dev->databits, ( dev->parity == N ? "N": ( dev->parity == O ? "O" : "E" )), dev->stopbits );
00220   if( (dev->fd = open((dev->ttyport), (O_RDWR | O_NOCTTY), 0)) < 0 )
00221   {
00222     return -1;
00223   }
00224   amtecDeviceSetParams(dev);
00225   return dev->fd;
00226 }
00227                                                                                           
00228 int waitForETX(int fd, unsigned char *buf, int *len)
00229 {
00230   static int pos, loop, val;
00231 #ifdef IO_DEBUG
00232   int i;
00233 #endif
00234   pos = 0;
00235   loop = 0;
00236   while (loop < MAX_NUM_LOOPS) {
00237     val = bytesWaiting(fd);
00238     if (val > 0) {
00239       if(pos + val >= MAX_ACMD_SIZE) return (0);
00240       read(fd, &(buf[pos]), val);
00241 #ifdef IO_DEBUG
00242       for(i=0;i<val;i++)
00243         fprintf(stderr, "[0x%s%x]", buf[pos+i]<16?"0":"", buf[pos+i]);
00244 #endif
00245       if (buf[pos + val - 1] == B_ETX) {
00246         *len = pos + val - 1;
00247 #ifdef IO_DEBUG
00248         fprintf(stderr, "\n");
00249 #endif
00250         return (1);
00251       }
00252       pos += val;
00253     } else {
00254       usleep(1000);
00255       loop++;
00256     }
00257   }
00258 #ifdef IO_DEBUG
00259   fprintf(stderr, "\n");
00260 #endif
00261   return (0);
00262 }
00263                                                                                                           
00264 int waitForAnswer(int fd, unsigned char *buf, int *len)
00265 {
00266   int loop = 0;
00267   *len = 0;
00268 #ifdef IO_DEBUG
00269   fprintf(stderr, "<--- ");
00270 #endif
00271   while (loop < MAX_NUM_LOOPS) {
00272     if (bytesWaiting(fd)) {
00273       read(fd, &(buf[0]), 1);
00274 #ifdef IO_DEBUG
00275       fprintf(stderr, "(0x%s%x)", buf[0]<16?"0":"", buf[0]);
00276 #endif
00277       if (buf[0] == B_STX) {
00278         return (waitForETX(fd, buf, len));
00279       }
00280     } else {
00281       usleep(1000);
00282       loop++;
00283     }
00284   }
00285 #ifdef IO_DEBUG
00286   fprintf(stderr, "\n");
00287 #endif
00288   return (0);
00289 }
00290                                                                                                                         
00291 int writeData(int fd, unsigned char *buf, int nChars)
00292 {
00293   int written = 0;
00294   while (nChars > 0) {
00295     written = write(fd, buf, nChars);
00296     if (written < 0) {
00297       return 0;
00298     } else {
00299       nChars -= written;
00300       buf += written;
00301     }
00302     usleep(1000);
00303   }
00304   return 1;
00305 }
00306                                                                                                                                 
00307 int amtecSendCommand(amtec_powercube_device_p dev, int id, unsigned char *cmd, int len)
00308 {
00309   static int i, ctr, add;
00310   static unsigned char rcmd[MAX_ACMD_SIZE];
00311   static unsigned char bcc;
00312   static unsigned char umnr;
00313   static unsigned char lmnr;
00314                                                                                                                                             
00315 #ifdef IO_DEBUG
00316   fprintf(stderr, "\n---> ");
00317   for(i=0;i<len;i++) {
00318     fprintf(stderr, "(0x%s%x)", cmd[i]<16?"0":"", cmd[i]);
00319   }
00320   fprintf(stderr, "\n");
00321 #endif
00322                                                                                                                                                   
00323   add = 0;
00324   lmnr = id & 7;
00325   lmnr = lmnr << 5;
00326   umnr = id >> 3;
00327   umnr = umnr | 4;
00328   for (i = 0; i < len; i++) {
00329     if ((cmd[i] == 0x02) || (cmd[i] == 0x03) || (cmd[i] == 0x10)) {
00330       add++;
00331     }
00332   }
00333   lmnr = lmnr + len;
00334   rcmd[0] = B_STX;
00335   rcmd[1] = umnr;
00336   rcmd[2] = lmnr;
00337   ctr = 3;
00338   for (i = 0; i < len; i++) {
00339     switch (cmd[i]) {
00340     case 0x02:
00341       rcmd[ctr] = 0x10;
00342       rcmd[++ctr] = 0x82;
00343       break;
00344     case 0x03:
00345       rcmd[ctr] = 0x10;
00346       rcmd[++ctr] = 0x83;
00347       break;
00348     case 0x10:
00349       rcmd[ctr] = 0x10;
00350       rcmd[++ctr] = 0x90;
00351       break;
00352     default:
00353       rcmd[ctr] = cmd[i];
00354     }
00355     ctr++;
00356   }
00357   bcc = id;
00358   for (i = 0; i < len; i++) {
00359     bcc += cmd[i];
00360   }
00361   bcc = bcc + (bcc >> 8);
00362   switch (bcc) {
00363   case 0x02:
00364     rcmd[ctr++] = 0x10;
00365     rcmd[ctr++] = 0x82;
00366     break;
00367   case 0x03:
00368     rcmd[ctr++] = 0x10;
00369     rcmd[ctr++] = 0x83;
00370     break;
00371   case 0x10:
00372     rcmd[ctr++] = 0x10;
00373     rcmd[ctr++] = 0x90;
00374     break;
00375   default:
00376     rcmd[ctr++] = bcc;
00377   }
00378   rcmd[ctr++] = B_ETX;
00379                                                                                                                                                                                     
00380 #ifdef IO_DEBUG
00381   fprintf(stderr, "-*-> ");
00382   for(i=0;i<ctr;i++) {
00383     fprintf(stderr, "(0x%s%x)", rcmd[i]<16?"0":"", rcmd[i]);
00384   }
00385   fprintf(stderr, "\n");
00386 #endif
00387                                                                                                                                                                                           
00388   if (writeData(dev->fd, rcmd, ctr))
00389   {
00390     return (1);
00391   }
00392   else
00393   {
00394     return (0);
00395   }
00396 }
00397                                                                                                                                                                                             
00398 void convertBuffer(unsigned char *cmd, int *len)
00399 {
00400   int i, j;
00401   for (i = 0; i < *len; i++)
00402   {
00403     if (cmd[i] == B_DLE)
00404     {
00405       switch (cmd[i + 1])
00406       {
00407       case 0x82:
00408         cmd[i] = 0x02;
00409         for (j = i + 2; j < *len; j++)
00410           cmd[j - 1] = cmd[j];
00411         (*len)--;
00412         break;
00413       case 0x83:
00414         cmd[i] = 0x03;
00415         for (j = i + 2; j < *len; j++)
00416           cmd[j - 1] = cmd[j];
00417         (*len)--;
00418         break;
00419       case 0x90:
00420         cmd[i] = 0x10;
00421         for (j = i + 2; j < *len; j++)
00422           cmd[j - 1] = cmd[j];
00423         (*len)--;
00424         break;
00425       }
00426     }
00427   }
00428 }
00429                                                                                                                                                                                                   
00430 int amtecGetAnswer(amtec_powercube_device_p dev, unsigned char *cmd, int *len)
00431 {
00432 #ifdef IO_DEBUG
00433   int i;
00434 #endif
00435   if (waitForAnswer(dev->fd, cmd, len))
00436   {
00437 #ifdef IO_DEBUG
00438     fprintf(stderr, "<=== ");
00439     for(i=0;i<*len;i++)
00440       fprintf(stderr, "[0x%s%x]", cmd[i]<16?"0":"", cmd[i]);
00441     fprintf(stderr, "\n");
00442 #endif
00443     convertBuffer(cmd, len);
00444 #ifdef IO_DEBUG
00445     fprintf(stderr, "<=p= ");
00446     for(i=0;i<*len;i++)
00447       fprintf(stderr, "[0x%s%x]", cmd[i]<16?"0":"", cmd[i]);
00448     fprintf(stderr, "\n");
00449 #endif
00450     return (1);
00451   } else {
00452     return (0);
00453   }
00454 }


amtec
Author(s): Charles DuHadway, Benjamin Pitzer (Maintained by Benjamin Pitzer)
autogenerated on Mon Oct 6 2014 10:10:36