$search
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 #include <termios.h> 00041 #include <unistd.h> 00042 #include <fcntl.h> 00043 #include <errno.h> 00044 #include <string.h> 00045 #include <sys/types.h> 00046 #include <sys/stat.h> 00047 #include <sys/ioctl.h> 00048 #include <sys/time.h> 00049 #include <linux/serial.h> 00050 #include "amtec_io.h" 00051 00052 //#define IO_DEBUG 00053 00054 int iParity(enum PARITY_TYPE par) 00055 { 00056 if (par == N) 00057 return (IGNPAR); 00058 else 00059 return (INPCK); 00060 } 00061 00062 int iSoftControl(int flowcontrol) 00063 { 00064 if (flowcontrol) 00065 return (IXON); 00066 else 00067 return (IXOFF); 00068 } 00069 00070 int cDataSize(int numbits) 00071 { 00072 switch (numbits) { 00073 case 5: 00074 return (CS5); 00075 break; 00076 case 6: 00077 return (CS6); 00078 break; 00079 case 7: 00080 return (CS7); 00081 break; 00082 case 8: 00083 return (CS8); 00084 break; 00085 default: 00086 return (CS8); 00087 break; 00088 } 00089 } 00090 00091 int cStopSize(int numbits) 00092 { 00093 if (numbits == 2) 00094 return (CSTOPB); 00095 else 00096 return (0); 00097 } 00098 00099 int cFlowControl(int flowcontrol) 00100 { 00101 if (flowcontrol) 00102 return (CRTSCTS); 00103 else 00104 return (CLOCAL); 00105 } 00106 00107 int cParity(enum PARITY_TYPE par) 00108 { 00109 if (par != N) { 00110 if (par == O) 00111 return (PARENB | PARODD); 00112 else 00113 return (PARENB); 00114 } else 00115 return (0); 00116 } 00117 00118 int cBaudrate(int baudrate) 00119 { 00120 switch (baudrate) { 00121 case 0: 00122 return (B0); 00123 break; 00124 case 300: 00125 return (B300); 00126 break; 00127 case 600: 00128 return (B600); 00129 break; 00130 case 1200: 00131 return (B1200); 00132 break; 00133 case 2400: 00134 return (B2400); 00135 break; 00136 case 4800: 00137 return (B4800); 00138 break; 00139 case 9600: 00140 return (B9600); 00141 break; 00142 case 19200: 00143 return (B19200); 00144 break; 00145 case 38400: 00146 return (B38400); 00147 break; 00148 case 57600: 00149 return (B57600); 00150 break; 00151 case 115200: 00152 return (B115200); 00153 break; 00154 case 500000: 00155 /* to use 500k you have to change the entry of B460800 in you kernel: 00156 /usr/src/linux/drivers/usb/serial/ftdi_sio.h: 00157 ftdi_8U232AM_48MHz_b460800 = 0x0006 */ 00158 return (B460800); 00159 break; 00160 default: 00161 return (B9600); 00162 break; 00163 } 00164 } 00165 00166 long bytesWaiting(int sd) 00167 { 00168 long available = 0; 00169 if (ioctl(sd, FIONREAD, &available) == 0) 00170 return available; 00171 else 00172 return -1; 00173 } 00174 00175 void amtecDeviceSetParams(amtec_powercube_device_p dev) 00176 { 00177 struct termios ctio; 00178 00179 tcgetattr(dev->fd, &ctio); /* save current port settings */ 00180 00181 ctio.c_iflag = iSoftControl(dev->swf) | iParity(dev->parity); 00182 ctio.c_oflag = 0; 00183 ctio.c_cflag = CREAD | cFlowControl(dev->hwf || dev->swf) 00184 | cParity(dev->parity) 00185 | cDataSize(dev->databits) 00186 | cStopSize(dev->stopbits); 00187 ctio.c_lflag = 0; 00188 ctio.c_cc[VTIME] = 0; /* inter-character timer unused */ 00189 ctio.c_cc[VMIN] = 0; /* blocking read until 0 chars received */ 00190 00191 cfsetispeed(&ctio, (speed_t) cBaudrate(dev->baud)); 00192 cfsetospeed(&ctio, (speed_t) cBaudrate(dev->baud)); 00193 00194 tcflush(dev->fd, TCIFLUSH); 00195 tcsetattr(dev->fd, TCSANOW, &ctio); 00196 } 00197 00198 void amtecDeviceSetBaudrate(amtec_powercube_device_p dev, int brate) 00199 { 00200 struct termios ctio; 00201 00202 tcgetattr(dev->fd, &ctio); /* save current port settings */ 00203 00204 cfsetispeed(&ctio, (speed_t) cBaudrate(brate)); 00205 cfsetospeed(&ctio, (speed_t) cBaudrate(brate)); 00206 00207 tcflush(dev->fd, TCIFLUSH); 00208 tcsetattr(dev->fd, TCSANOW, &ctio); 00209 } 00210 00211 int amtecDeviceConnectPort(amtec_powercube_device_p dev) 00212 { 00213 fprintf(stderr, "\nset device:\n"); 00214 fprintf(stderr, " port = %s\n", dev->ttyport); 00215 fprintf(stderr, " baud = %d\n", dev->baud); 00216 fprintf(stderr, " params = %d%s%d\n", dev->databits, 00217 dev->parity == N ? "N": dev->parity == O ? "O" : "E", 00218 dev->stopbits); 00219 if ((dev->fd = open((dev->ttyport), (O_RDWR | O_NOCTTY), 0)) < 0) 00220 return (-1); 00221 amtecDeviceSetParams(dev); 00222 return (dev->fd); 00223 } 00224 00225 int waitForETX(int fd, unsigned char *buf, int *len) 00226 { 00227 static int pos, loop, val; 00228 #ifdef IO_DEBUG 00229 int i; 00230 #endif 00231 pos = 0; 00232 loop = 0; 00233 while (loop < MAX_NUM_LOOPS) { 00234 val = bytesWaiting(fd); 00235 if (val > 0) { 00236 if(pos + val >= MAX_ACMD_SIZE) return (0); 00237 read(fd, &(buf[pos]), val); 00238 #ifdef IO_DEBUG 00239 for(i=0;i<val;i++) 00240 fprintf(stderr, "[0x%s%x]", buf[pos+i]<16?"0":"", buf[pos+i]); 00241 #endif 00242 if (buf[pos + val - 1] == B_ETX) { 00243 *len = pos + val - 1; 00244 #ifdef IO_DEBUG 00245 fprintf(stderr, "\n"); 00246 #endif 00247 return (1); 00248 } 00249 pos += val; 00250 } else { 00251 usleep(1000); 00252 loop++; 00253 } 00254 } 00255 #ifdef IO_DEBUG 00256 fprintf(stderr, "\n"); 00257 #endif 00258 return (0); 00259 } 00260 00261 int waitForAnswer(int fd, unsigned char *buf, int *len) 00262 { 00263 int loop = 0; 00264 *len = 0; 00265 #ifdef IO_DEBUG 00266 fprintf(stderr, "<--- "); 00267 #endif 00268 while (loop < MAX_NUM_LOOPS) { 00269 if (bytesWaiting(fd)) { 00270 read(fd, &(buf[0]), 1); 00271 #ifdef IO_DEBUG 00272 fprintf(stderr, "(0x%s%x)", buf[0]<16?"0":"", buf[0]); 00273 #endif 00274 if (buf[0] == B_STX) { 00275 return (waitForETX(fd, buf, len)); 00276 } 00277 } else { 00278 usleep(1000); 00279 loop++; 00280 } 00281 } 00282 #ifdef IO_DEBUG 00283 fprintf(stderr, "\n"); 00284 #endif 00285 return (0); 00286 } 00287 00288 int writeData(int fd, unsigned char *buf, int nChars) 00289 { 00290 int written = 0; 00291 while (nChars > 0) { 00292 written = write(fd, buf, nChars); 00293 if (written < 0) { 00294 return 0; 00295 } else { 00296 nChars -= written; 00297 buf += written; 00298 } 00299 usleep(1000); 00300 } 00301 return 1; 00302 } 00303 00304 int amtecSendCommand(amtec_powercube_device_p dev, int id, unsigned char *cmd, int len) 00305 { 00306 static int i, ctr, add; 00307 static unsigned char rcmd[MAX_ACMD_SIZE]; 00308 static unsigned char bcc; 00309 static unsigned char umnr; 00310 static unsigned char lmnr; 00311 00312 #ifdef IO_DEBUG 00313 fprintf(stderr, "\n---> "); 00314 for(i=0;i<len;i++) { 00315 fprintf(stderr, "(0x%s%x)", cmd[i]<16?"0":"", cmd[i]); 00316 } 00317 fprintf(stderr, "\n"); 00318 #endif 00319 00320 add = 0; 00321 lmnr = id & 7; 00322 lmnr = lmnr << 5; 00323 umnr = id >> 3; 00324 umnr = umnr | 4; 00325 for (i = 0; i < len; i++) { 00326 if ((cmd[i] == 0x02) || (cmd[i] == 0x03) || (cmd[i] == 0x10)) { 00327 add++; 00328 } 00329 } 00330 lmnr = lmnr + len; 00331 rcmd[0] = B_STX; 00332 rcmd[1] = umnr; 00333 rcmd[2] = lmnr; 00334 ctr = 3; 00335 for (i = 0; i < len; i++) { 00336 switch (cmd[i]) { 00337 case 0x02: 00338 rcmd[ctr] = 0x10; 00339 rcmd[++ctr] = 0x82; 00340 break; 00341 case 0x03: 00342 rcmd[ctr] = 0x10; 00343 rcmd[++ctr] = 0x83; 00344 break; 00345 case 0x10: 00346 rcmd[ctr] = 0x10; 00347 rcmd[++ctr] = 0x90; 00348 break; 00349 default: 00350 rcmd[ctr] = cmd[i]; 00351 } 00352 ctr++; 00353 } 00354 bcc = id; 00355 for (i = 0; i < len; i++) { 00356 bcc += cmd[i]; 00357 } 00358 bcc = bcc + (bcc >> 8); 00359 switch (bcc) { 00360 case 0x02: 00361 rcmd[ctr++] = 0x10; 00362 rcmd[ctr++] = 0x82; 00363 break; 00364 case 0x03: 00365 rcmd[ctr++] = 0x10; 00366 rcmd[ctr++] = 0x83; 00367 break; 00368 case 0x10: 00369 rcmd[ctr++] = 0x10; 00370 rcmd[ctr++] = 0x90; 00371 break; 00372 default: 00373 rcmd[ctr++] = bcc; 00374 } 00375 rcmd[ctr++] = B_ETX; 00376 00377 #ifdef IO_DEBUG 00378 fprintf(stderr, "-*-> "); 00379 for(i=0;i<ctr;i++) { 00380 fprintf(stderr, "(0x%s%x)", rcmd[i]<16?"0":"", rcmd[i]); 00381 } 00382 fprintf(stderr, "\n"); 00383 #endif 00384 00385 if (writeData(dev->fd, rcmd, ctr)) { 00386 return (1); 00387 } else { 00388 return (0); 00389 } 00390 } 00391 00392 void convertBuffer(unsigned char *cmd, int *len) 00393 { 00394 int i, j; 00395 for (i = 0; i < *len; i++) { 00396 if (cmd[i] == B_DLE) { 00397 switch (cmd[i + 1]) { 00398 case 0x82: 00399 cmd[i] = 0x02; 00400 for (j = i + 2; j < *len; j++) 00401 cmd[j - 1] = cmd[j]; 00402 (*len)--; 00403 break; 00404 case 0x83: 00405 cmd[i] = 0x03; 00406 for (j = i + 2; j < *len; j++) 00407 cmd[j - 1] = cmd[j]; 00408 (*len)--; 00409 break; 00410 case 0x90: 00411 cmd[i] = 0x10; 00412 for (j = i + 2; j < *len; j++) 00413 cmd[j - 1] = cmd[j]; 00414 (*len)--; 00415 break; 00416 } 00417 } 00418 } 00419 } 00420 00421 int amtecGetAnswer(amtec_powercube_device_p dev, unsigned char *cmd, int *len) 00422 { 00423 #ifdef IO_DEBUG 00424 int i; 00425 #endif 00426 if (waitForAnswer(dev->fd, cmd, len)) { 00427 #ifdef IO_DEBUG 00428 fprintf(stderr, "<=== "); 00429 for(i=0;i<*len;i++) 00430 fprintf(stderr, "[0x%s%x]", cmd[i]<16?"0":"", cmd[i]); 00431 fprintf(stderr, "\n"); 00432 #endif 00433 convertBuffer(cmd, len); 00434 #ifdef IO_DEBUG 00435 fprintf(stderr, "<=p= "); 00436 for(i=0;i<*len;i++) 00437 fprintf(stderr, "[0x%s%x]", cmd[i]<16?"0":"", cmd[i]); 00438 fprintf(stderr, "\n"); 00439 #endif 00440 return (1); 00441 } else { 00442 return (0); 00443 } 00444 }