Initial commit.
[betaflight.git] / support / stmloader / serial.c
blobb11fa4923df51d333807f9a357d819d18ca9bcf2
1 /*
2 This file is part of AutoQuad.
4 AutoQuad is free software: you can redistribute it and/or modify
5 it under the terms of the GNU General Public License as published by
6 the Free Software Foundation, either version 3 of the License, or
7 (at your option) any later version.
9 AutoQuad is distributed in the hope that it will be useful,
10 but WITHOUT ANY WARRANTY; without even the implied warranty of
11 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 GNU General Public License for more details.
13 You should have received a copy of the GNU General Public License
14 along with AutoQuad. If not, see <http://www.gnu.org/licenses/>.
16 Copyright © 2011 Bill Nesbitt
19 #ifndef _GNU_SOURCE
20 #define _GNU_SOURCE
21 #endif
23 #include "serial.h"
24 #include <stdio.h>
25 #include <unistd.h>
26 #include <termios.h>
27 #include <fcntl.h>
28 #include <stdlib.h>
29 #include <sys/select.h>
30 #include <string.h>
32 serialStruct_t *initSerial(const char *port, unsigned int baud, char ctsRts) {
33 serialStruct_t *s;
34 struct termios options;
35 unsigned int brate;
37 s = (serialStruct_t *)calloc(1, sizeof(serialStruct_t));
39 s->fd = open(port, O_RDWR | O_NOCTTY | O_NDELAY);
41 if (s->fd == -1) {
42 free(s);
43 return 0;
46 fcntl(s->fd, F_SETFL, 0); // clear all flags on descriptor, enable direct I/O
48 // bzero(&options, sizeof(options));
49 // memset(&options, 0, sizeof(options));
50 tcgetattr(s->fd, &options);
52 #ifdef B921600
53 switch (baud) {
54 case 9600:
55 brate = B9600;
56 break;
57 case 19200:
58 brate = B19200;
59 break;
60 case 38400:
61 brate = B38400;
62 break;
63 case 57600:
64 brate = B57600;
65 break;
66 case 115200:
67 brate = B115200;
68 break;
69 case 230400:
70 brate = B230400;
71 break;
72 case 460800:
73 brate = B460800;
74 break;
75 case 921600:
76 brate = B921600;
77 break;
78 default:
79 brate = B115200;
80 break;
82 options.c_cflag = brate;
83 #else // APPLE
84 cfsetispeed(&options, baud);
85 cfsetospeed(&options, baud);
86 #endif
88 options.c_cflag |= CRTSCTS | CS8 | CLOCAL | CREAD;
89 options.c_iflag = IGNPAR;
90 options.c_iflag &= (~(IXON|IXOFF|IXANY)); // turn off software flow control
91 options.c_oflag = 0;
93 /* set input mode (non-canonical, no echo,...) */
94 options.c_lflag = 0;
96 options.c_cc[VTIME] = 0; /* inter-character timer unused */
97 options.c_cc[VMIN] = 1; /* blocking read until 1 chars received */
99 #ifdef CCTS_OFLOW
100 options.c_cflag |= CCTS_OFLOW;
101 #endif
103 if (!ctsRts)
104 options.c_cflag &= ~(CRTSCTS); // turn off hardware flow control
106 // set the new port options
107 tcsetattr(s->fd, TCSANOW, &options);
109 return s;
112 void serialFree(serialStruct_t *s) {
113 if (s) {
114 if (s->fd)
115 close(s->fd);
116 free (s);
120 void serialNoParity(serialStruct_t *s) {
121 struct termios options;
123 tcgetattr(s->fd, &options); // read serial port options
125 options.c_cflag &= ~(PARENB | CSTOPB);
127 tcsetattr(s->fd, TCSANOW, &options);
130 void serialEvenParity(serialStruct_t *s) {
131 struct termios options;
133 tcgetattr(s->fd, &options); // read serial port options
135 options.c_cflag |= (PARENB);
136 options.c_cflag &= ~(PARODD | CSTOPB);
138 tcsetattr(s->fd, TCSANOW, &options);
141 void serialWriteChar(serialStruct_t *s, unsigned char c) {
142 char ret;
144 ret = write(s->fd, &c, 1);
147 void serialWrite(serialStruct_t *s, const char *str, unsigned int len) {
148 char ret;
150 ret = write(s->fd, str, len);
153 unsigned char serialAvailable(serialStruct_t *s) {
154 fd_set fdSet;
155 struct timeval timeout;
157 FD_ZERO(&fdSet);
158 FD_SET(s->fd, &fdSet);
159 memset((char *)&timeout, 0, sizeof(timeout));
161 if (select(s->fd+1, &fdSet, 0, 0, &timeout) == 1)
162 return 1;
163 else
164 return 0;
167 void serialFlush(serialStruct_t *s) {
168 while (serialAvailable(s))
169 serialRead(s);
172 unsigned char serialRead(serialStruct_t *s) {
173 char ret;
174 unsigned char c;
176 ret = read(s->fd, &c, 1);
178 return c;