pixhawk串口读取传感器数据


1、 Pixhawk板上串口说明: 

  
这里写图片描述
 


  
测试
使用Pixhawk板上TELEM2接口的USART2,对应的Nuttx UART设备文件尾
/dev/ttyS2
: 

  这里写图片描述

2 读取数据测试

步骤:

    • Firmware/src/modules中添加一个新的文件夹,命名为rw_uart
    • rw_uart文件夹中创建CMakeLists.txt文件,并输入以下内容:
      px4_add_module(
      MODULE modules__rw_uart
      MAIN rw_uart
      COMPILE_FLAGS
      -Os
      SRCS
      rw_uart.c
      DEPENDS
      platforms__common
      )
      这是CMake的编译脚本
    • rw_uart文件夹中创建rw_uart.c文件
    • 注册新添加的应用到NuttShell中。/src/Firmware/cmake/configs/nuttx_px4fmu-v2_default.cmake文件中添加如下内容:
      modules/rw_uart

上面表示把rw_uart.c编译成可以在nuttx里面运行的程序。

rw_uart.c

  

#include <stdio.h>
#include <termios.h>
#include <unistd.h>
#include <stdbool.h>
#include <errno.h>
#include <drivers/drv_hrt.h>
#include <string.h>
#include <systemlib/err.h>
#include <systemlib/systemlib.h>
#include <fcntl.h>
#include <sys/types.h>
#include <sys/stat.h>

__EXPORT int rw_uart_main(int argc, char *argv[]);

int set_uart_baudrate(const int fd, unsigned int baud);

int set_uart_baudrate(const int fd, unsigned int baud)
{
int speed;

switch (baud) {
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;
default:
warnx("ERR: baudrate: %d\n", baud);
return -EINVAL;
}

struct termios uart_config;

int termios_state;

/* fill the struct for the new configuration */
tcgetattr(fd, &uart_config);
/* clear ONLCR flag (which appends a CR for every LF) */
uart_config.c_oflag &= ~ONLCR;
/* no parity, one stop bit */
uart_config.c_cflag &= ~(CSTOPB | PARENB);
/* set baud rate */
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
warnx("ERR: %d (cfsetispeed)\n", termios_state);
return false;
}

if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
warnx("ERR: %d (cfsetospeed)\n", termios_state);
return false;
}

if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
warnx("ERR: %d (tcsetattr)\n", termios_state);
return false;
}

return true;
}

int rw_uart_main(int argc, char *argv[])
{
char data = '0';
char buffer[4] = "";

int uart_read = open("/dev/ttyS2", O_RDWR | O_NOCTTY);//打开串口设备

if (uart_read < 0) {
err(1, "failed to open port: %s", "/dev/ttyS2");
return -1;
}

if(false == set_uart_baudrate(uart_read,9600)){
printf("[YCM]set_uart_baudrate is failed\n");
return -1;
}
printf("[YCM]uart init is successful\n");

while(true){
read(uart_read,&data,1);
if(data == 'R'){
for(int i = 0;i <4;++i){
read(uart_read,&data,1);//读取串口数据
buffer[i] = data;
data = '0';
}
printf("%s\n",buffer);
}
}

return 0;
}

编译并刷固件
make clean
make px4fmu-v2_default
make up

查看app
在NSH终端中输入help,在Builtin Apps中出现rw_uart应用。
运行rw_uart应用(前提是模块与Pixhawk连接好)
在NSH终端中输入rw_uart,回车,查看串口数据的打印数据(TELEM2接口的USART2)。
以上就是简单的PIX里面的应用程序。可以从串口读取到数据到内部,可以看到避开了复杂的单片机配置过程,还是很方便的。

3、可以在启动文件中 系统启动的时候就开始运行读取串口的数据

/src/ROMFS/init.d/rc_mc_app下添加子启动


//mcu_avoid start /dev/ttyS6

//laser_gun start /dev/ttyS3

//laser_gun_shoot start /dev/ttyS3


版权声明:本文为Gen_Ye原创文章,遵循 CC 4.0 BY-SA 版权协议,转载请附上原文出处链接和本声明。
THE END
< <上一篇
下一篇>>