pixhawk Firmware串口serial4的使用
讨论区我现在在使用pixhawk Firmware串口。其中接口serial4\5目前空闲,我想编个应用程序使用串口收发数据。结果串口没有反应?
程序如下:
serial_fd = open("/dev/ttyS4", O_RDWR);
if (serial_fd < 0) {
printf("failed to open serial port\n");
return 0;
}
printf("open cam_serial port success!\n");
i = 0;
while(i<= 10)
{
sleep(1);
dprintf(serial_fd, "%d\n",i);
printf("serial send!\n");
i ++;
//nread = read(uart_fd, buf, sizeof(buf));
}
close(serial_fd);
4 个回复
hedong - 开发者
赞同来自:
1 你没有设置波特率等属性
2 SERIA5 是内核调试端口,建议不要使用
正确的做法是下面这样:
int open_uart(int baud, const char uart_name, struct termios *uart_config_original)
{
/ process baud rate */
int speed;
switch (baud) {
case 0: speed = B0; break;
case 50: speed = B50; break;
case 75: speed = B75; break;
case 110: speed = B110; break;
case 134: speed = B134; break;
case 150: speed = B150; break;
case 200: speed = B200; break;
case 300: speed = B300; break;
case 600: speed = B600; break;
case 1200: speed = B1200; break;
case 1800: speed = B1800; break;
case 2400: speed = B2400; break;
case 4800: speed = B4800; break;
case 9600: speed = B9600; break;
case 19200: speed = B19200; break;
case 38400: speed = B38400; break;
case 57600: speed = B57600; break;
case 115200: speed = B115200; break;
case 230400: speed = B230400; break;
case 460800: speed = B460800; break;
case 921600: speed = B921600; break;
default:
warnx("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\t9600, 19200, 38400, 57600\t\n115200\n230400\n460800\n921600\n",
baud);
return -EINVAL;
}
/* open uart */
int _uart_fd = open(uart_name, O_RDWR | O_NOCTTY);
if (_uart_fd < 0) {
return _uart_fd;
}
/* Try to set baud rate */
struct termios uart_config;
int termios_state;
/* Back up the original uart configuration to restore it after exit */
if ((termios_state = tcgetattr(_uart_fd, uart_config_original)) < 0) {
warnx("ERR GET CONF %s: %d\n", uart_name, termios_state);
close(_uart_fd);
return -1;
}
/* Fill the struct for the new configuration */
tcgetattr(_uart_fd, &uart_config);
/* Clear ONLCR flag (which appends a CR for every LF) */
uart_config.c_oflag &= ~ONLCR;
/* USB serial is indicated by /dev/ttyACM0*/
if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/ttyACM1") != OK) {
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
warnx("ERR SET BAUD %s: %d\n", uart_name, termios_state);
close(_uart_fd);
return -1;
}
}
if ((termios_state = tcsetattr(_uart_fd, TCSANOW, &uart_config)) < 0) {
warnx("ERR SET CONF %s\n", uart_name);
close(_uart_fd);
return -1;
}
(void)tcgetattr(_uart_fd, &uart_config);
uart_config.c_cflag |= CRTS_IFLOW;
(void)tcsetattr(_uart_fd, TCSANOW, &uart_config);
/* setup output flow control */
// if (enable_flow_control(_uart_fd,true)) {
// warnx("hardware flow control not supported");
// }
return _uart_fd;
}
void main()
{
struct termios uart_config_original;
fd = open_uart(921600, "/dev/ttyS2", &uart_config_original);
uint8_t buf[32];
int nread = read(fd, buf, sizeof(buf));
}