APM:Libraries
UART_utils.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2017 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include <AP_HAL/AP_HAL.h>
18 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
19 
20 #include "UARTDriver.h"
21 
22 #if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(__APPLE__)
23 #define USE_TERMIOS
24 #endif
25 
26 #ifdef USE_TERMIOS
27 #include <termios.h>
28 #else
29 #include <asm/termbits.h>
30 #endif
31 
32 #include <string.h>
33 #include <sys/ioctl.h>
34 #include <sys/stat.h>
35 #include <sys/types.h>
36 
38 {
39  if (_fd < 0) {
40  return false;
41  }
42 #ifdef USE_TERMIOS
43  struct termios t;
44  tcgetattr(_fd, &t);
45  cfsetspeed(&t, speed);
46  tcsetattr(_fd, TCSANOW, &t);
47 #else
48  struct termios2 tc;
49  memset(&tc, 0, sizeof(tc));
50  if (ioctl(_fd, TCGETS2, &tc) == -1) {
51  return false;
52  }
53 
54  /* speed is configured by c_[io]speed */
55  tc.c_cflag &= ~CBAUD;
56  tc.c_cflag |= BOTHER;
57  tc.c_ispeed = speed;
58  tc.c_ospeed = speed;
59  if (ioctl(_fd, TCSETS2, &tc) == -1) {
60  return false;
61  }
62  if (ioctl(_fd, TCFLSH, TCIOFLUSH) == -1) {
63  return false;
64  }
65 #endif
66 
67  return true;
68 }
69 
71 {
72  if (_fd < 0) {
73  return;
74  }
75 #ifdef USE_TERMIOS
76  struct termios t;
77 
78  tcgetattr(_fd, &t);
79 #else
80  struct termios2 t;
81  memset(&t, 0, sizeof(t));
82  if (ioctl(_fd, TCGETS2, &t) == -1) {
83  return;
84  }
85 #endif
86  if (v != 0) {
87  // enable parity
88  t.c_cflag |= PARENB;
89  if (v == 1) {
90  t.c_cflag |= PARODD;
91  } else {
92  t.c_cflag &= ~PARODD;
93  }
94  }
95  else {
96  // disable parity
97  t.c_cflag &= ~PARENB;
98  }
99 
100 #ifdef USE_TERMIOS
101  tcsetattr(_fd, TCSANOW, &t);
102 #else
103  ioctl(_fd, TCSETS2, &t);
104 #endif
105 }
106 
108 {
109  if (_fd < 0) {
110  return;
111  }
112 #ifdef USE_TERMIOS
113  struct termios t;
114 
115  tcgetattr(_fd, &t);
116 #else
117  struct termios2 t;
118  memset(&t, 0, sizeof(t));
119  if (ioctl(_fd, TCGETS2, &t) == -1) {
120  return;
121  }
122 #endif
123 
124  if (n > 1) {
125  t.c_cflag |= CSTOPB;
126  } else {
127  t.c_cflag &= ~CSTOPB;
128  }
129 
130 #ifdef USE_TERMIOS
131  tcsetattr(_fd, TCSANOW, &t);
132 #else
133  ioctl(_fd, TCSETS2, &t);
134 #endif
135 }
136 
137 #endif
bool set_speed(int speed)
Definition: UART_utils.cpp:37
void configure_parity(uint8_t v) override
Definition: UART_utils.cpp:70
float v
Definition: Printf.cpp:15
void set_stop_bits(int n) override
Definition: UART_utils.cpp:107