pixhawk + uart串口
- 新建一个uart.msg文件
- 新建一个文件读取串口的数据
- 使其在程序中传递串口数据,并进行运算
读取串口数据(坐标信息)
准备工作
- 准备一个uart设备,能够发送数据。这里我使用32开发板作为载体,向px4发送坐标信息,发送的数据格式为 ‘s:1234,1234,1234\r’单位为毫米。
开发px4代码
定义消息
首先在msg的文件夹下创建uart_pos.msg
文件,然后在里面自定义数据类型,uint32 id # ID of the estimator, commonly the component ID of the incoming message
int32 int_x # Z postiton in meters in the NED earth-fixed frame
int32 int_y # Z postiton in meters in the NED earth-fixed frame
int32 int_z # Z postiton in meters in the NED earth-fixed frame
- CMakeLists.txt中注册
在./msg/CMakeLists.txt
中注册1
2
3
4
5set(msg_files
...
wind_estimate.msg
uart_pos.msg
)
读取uart数据
在./src/modules
中新建文件夹read_uart
在文件夹中添加read_uart.c
与CMakelists.txt
read_uart.c
内容主要如下:初始化
px4使用nuttx操作系统,所以我们不能直接像使用32库的方式来配置uart,nuttx 提供了uart的驱动,我们 只需要取调用就可以了:/*初始化串口*/ int uart_read = uart_init(uart_name); if(false == uart_read)return -1; /*设置波特率*/ if(false == set_uart_baudrate(uart_read,115200)){ printf("set_uart_baudrate is failed\n"); return -1; } printf("uart init is successful\n");
- uart_init(uart_name) 返回一个句柄,uart_name 可以在rcS脚本中找到,其中写着uart的具体名称:
1
2
3
4
5
6
7
8
9/*
* TELEM1 : /dev/ttyS1
* TELEM2 : /dev/ttyS2
* GPS : /dev/ttyS3
* NSH : /dev/ttyS5
* SERIAL4: /dev/ttyS6
* N/A : /dev/ttyS4
* IO DEBUG (RX only):/dev/ttyS0
*/ 读取数据
while(!thread_should_exit){ read(uart_read,&data,1); read_uart(data); }
数据保存到data
- uart_init(uart_name) 返回一个句柄,uart_name 可以在rcS脚本中找到,其中写着uart的具体名称:
- 数据处理与数据发送
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32int read_uart(char data)
{
static int i=0;
static char rx_buff[48];
static char state=0;
static int times = 0;
times ++;
// int x,y,z;
if(state ==0 || data == 's')//数据起始位
{
i=0;
memset(rx_buff,0,sizeof(rx_buff));
state = 1;
}else if(state == 1&&data ==':'){
state = 2;
}else if(state ==2 ){
if(data == '\r')//数据结束位
{
sscanf(rx_buff,"%d,%d,%d",&uart_data.int_x,&uart_data.int_y,&uart_data.int_z);
if(times %500 == 0)//发送到控制台
mavlink_and_console_log_info(&mavlink_uart_pub, "[uart]ok %d %d %d",uart_data.int_x,uart_data.int_y,uart_data.int_z);
state = 0;
return 0;
}
rx_buff[i] = data;
i++;
}
else state = 0;
return 0;
}
- 注册到飞控中
./src/modules/read_uart/CMakelists.txt
中:
添加
1
2
3
4
5
6
7
8
9
10
px4_add_module(
MODULE modules__read_uart
MAIN read_uart_sensor
COMPILE_FLAGS
-Os
SRCS
read_uart.c
DEPENDS
platforms__common
)
2. `./cmake/config/nuttx_px4fmu-v2_default.cmake`添加
1
modules/sensors
- 在控制台输入
make px4fmu-v2_default upload
将生成的固件下载到pix中,然后在qgc的控制台上输入?
应该能看到7490
这时接着输入read_uart_sensor start /dev/ttyS4
(ttyS4是根据你连接的串口,
- TELEM1 : /dev/ttyS1
- TELEM2 : /dev/ttyS2
- GPS : /dev/ttyS3
- NSH : /dev/ttyS5
- SERIAL4: /dev/ttyS6
- N/A : /dev/ttyS4
- IO DEBUG (RX only):/dev/ttyS0)
8028
这时你应该可以看到数据在通知栏和控制台上
应用到的文件
[点这里](https://download.csdn.net/download/kurumi_guyi/10296141)