Skip to content

Commit e0abe70

Browse files
authored
SBUS on Linux: replace termios with termios2 and add UNKNOWN UART WQ
1 parent c8a58c5 commit e0abe70

File tree

3 files changed

+38
-52
lines changed

3 files changed

+38
-52
lines changed

platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,7 @@ static constexpr wq_config_t UART5{"wq:UART5", 1400, -21};
7979
static constexpr wq_config_t UART6{"wq:UART6", 1400, -22};
8080
static constexpr wq_config_t UART7{"wq:UART7", 1400, -23};
8181
static constexpr wq_config_t UART8{"wq:UART8", 1400, -24};
82+
static constexpr wq_config_t UART_UNKNOWN{"wq:UART_UNKNOWN", 1400, -25};
8283

8384
static constexpr wq_config_t lp_default{"wq:lp_default", 1700, -50};
8485

platforms/common/px4_work_queue/WorkQueueManager.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -196,9 +196,9 @@ serial_port_to_wq(const char *serial)
196196
return wq_configurations::UART8;
197197
}
198198

199-
PX4_ERR("unknown serial port: %s", serial);
199+
PX4_DEBUG("unknown serial port: %s", serial);
200200

201-
return wq_configurations::hp_default;
201+
return wq_configurations::UART_UNKNOWN;
202202
}
203203

204204
static void *

src/lib/rc/sbus.cpp

+35-50
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,6 @@
4141

4242
#include <fcntl.h>
4343
#include <unistd.h>
44-
#include <termios.h>
4544
#include <string.h>
4645

4746
#ifdef TIOCSSINGLEWIRE
@@ -58,7 +57,9 @@ using namespace time_literals;
5857

5958
#if defined(__PX4_LINUX)
6059
#include <sys/ioctl.h>
61-
#include <linux/serial_core.h>
60+
#include <asm-generic/termbits.h>
61+
#else
62+
#include <termios.h>
6263
#endif
6364

6465
#define SBUS_START_SYMBOL 0x0f
@@ -152,56 +153,40 @@ sbus_init(const char *device, bool singlewire)
152153
int
153154
sbus_config(int sbus_fd, bool singlewire)
154155
{
155-
#if defined(__PX4_LINUX)
156-
struct termios options;
157-
158-
if (tcgetattr(sbus_fd, &options) != 0) {
159-
return -1;
160-
}
161-
162-
tcflush(sbus_fd, TCIFLUSH);
163-
bzero(&options, sizeof(options));
164-
165-
options.c_cflag |= (CLOCAL | CREAD);
166-
options.c_cflag &= ~CSIZE;
167-
options.c_cflag |= CS8;
168-
options.c_cflag |= PARENB;
169-
options.c_cflag &= ~PARODD;
170-
options.c_iflag |= INPCK;
171-
options.c_cflag |= CSTOPB;
172-
173-
options.c_cc[VTIME] = 0;
174-
options.c_cc[VMIN] = 0;
175-
176-
cfsetispeed(&options, B38400);
177-
cfsetospeed(&options, B38400);
178-
179-
tcflush(sbus_fd, TCIFLUSH);
156+
int ret = -1;
180157

181-
if ((tcsetattr(sbus_fd, TCSANOW, &options)) != 0) {
182-
return -1;
183-
}
158+
#if defined(__PX4_LINUX)
184159

185-
int baud = 100000;
186-
struct serial_struct serials;
160+
struct termios2 tio = {};
187161

188-
if ((ioctl(sbus_fd, TIOCGSERIAL, &serials)) < 0) {
189-
return -1;
162+
if (0 != ioctl(sbus_fd, TCGETS2, &tio)) {
163+
return ret;
190164
}
191165

192-
serials.flags = ASYNC_SPD_CUST;
193-
serials.custom_divisor = serials.baud_base / baud;
194-
195-
if ((ioctl(sbus_fd, TIOCSSERIAL, &serials)) < 0) {
196-
return -1;
166+
/**
167+
* Setting serial port,8E2, non-blocking.100Kbps
168+
*/
169+
tio.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL
170+
| IXON);
171+
tio.c_iflag |= (INPCK | IGNPAR);
172+
tio.c_oflag &= ~OPOST;
173+
tio.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
174+
tio.c_cflag &= ~(CSIZE | CRTSCTS | PARODD | CBAUD);
175+
/**
176+
* use BOTHER to specify speed directly in c_[io]speed member
177+
*/
178+
tio.c_cflag |= (CS8 | CSTOPB | CLOCAL | PARENB | BOTHER | CREAD);
179+
tio.c_ispeed = 100000;
180+
tio.c_ospeed = 100000;
181+
tio.c_cc[VMIN] = 25;
182+
tio.c_cc[VTIME] = 0;
183+
184+
if (0 != ioctl(sbus_fd, TCSETS2, &tio)) {
185+
return ret;
197186
}
198187

199-
ioctl(sbus_fd, TIOCGSERIAL, &serials);
200-
201-
tcflush(sbus_fd, TCIFLUSH);
202-
return 0;
188+
ret = 0;
203189
#else
204-
int ret = -1;
205190

206191
if (sbus_fd >= 0) {
207192
struct termios t;
@@ -221,16 +206,16 @@ sbus_config(int sbus_fd, bool singlewire)
221206
#endif
222207
}
223208

224-
/* initialise the decoder */
225-
partial_frame_count = 0;
226-
last_rx_time = hrt_absolute_time();
227-
sbus_frame_drops = 0;
228-
229209
ret = 0;
230210
}
231211

232-
return ret;
233212
#endif
213+
/* initialise the decoder */
214+
partial_frame_count = 0;
215+
last_rx_time = hrt_absolute_time();
216+
sbus_frame_drops = 0;
217+
218+
return ret;
234219
}
235220

236221
void

0 commit comments

Comments
 (0)