最近突然感觉,能把开发程序的流程写清楚比开发程序本身还困难,所以之前写的文章都是毫无章法,想到哪写到哪,努力改变中。。。
之前开发了超声波测量距离的驱动,实质是px4的IO口操作。本次的操作很显然是操作px4的串口。
首先,介绍下硬件,我用的是Pixhawk2.4.8飞控,常用的串口6个,这六个串口在px4中对应的设备号如下:
TELEM1:/dev/ttyS1
TELEM2:/dev/ttyS2
GPS:/dev/ttyS3
SERIAL5/NSH:/dev/ttyS5
SERIAL4:/dev/ttyS4
下面贴出我写的串口读写云台角度的程序,本程序首先向云台发送一个指令,然后读取云台返回的数据,解析出角度数据获取云台当前的角度数据。
/*
* 串口读取函数
* rw_uart.c
*/
#include
#include
#include
#include
#include
#include
#include
#include
//#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include //引入 需要订阅sensor_combined 消息头文件
#include //引入 需要发布vehicle_attitude 消息头文件
__EXPORT int rw_uart_main(int argc, char *argv[]);
static int uart_init(char * uart_name);
static 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;
/* 以新的配置填充结构体 */
/* 设置某个选项,那么就使用"|="运算,
* 如果关闭某个选项就使用"&="和"~"运算
* */
tcgetattr(fd, &uart_config); // 获取终端参数
/* clear ONLCR flag (which appends a CR for every LF) */
uart_config.c_oflag &= ~ONLCR;// 将NL转换成CR(回车)-NL后输出。
/* 无偶校验,一个停止位 */
uart_config.c_cflag &= ~(CSTOPB | PARENB);// CSTOPB 使用两个停止位,PARENB 表示偶校验
/* 设置波特率 */
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;
}
// 设置与终端相关的参数,TCSANOW 立即改变参数
if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
warnx("ERR: %d (tcsetattr)\n", termios_state);
return false;
}
return true;
}
int uart_init(char * uart_name)
{
int serial_fd = open(uart_name, O_RDWR | O_NOCTTY);
/*Linux中,万物皆文件,打开串口设备和打开普通文件一样,使用的是open()系统调用*/
// 选项 O_NOCTTY 表示不能把本串口当成控制终端,否则用户的键盘输入信息将影响程序的执行
if (serial_fd < 0) {
err(1, "failed to open port: %s", uart_name);
return false;
}
// printf("Open the %s\n",serial_fd);
return serial_fd;
}
int rw_uart_main(int argc, char *argv[])
{
char senddata[8] = {0x55,0xAA,0xDC,0x04,0x00,0x00,0x04,0xE3};
unsigned char buffer[108];
double x,y;
//double ax,ay;
/*
* 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
*/
int uart_read = uart_init("/dev/ttyS3");//初始化串口设备
if(false == uart_read)
return -1;
if(false == set_uart_baudrate(uart_read,115200)){//设置波特率
printf("[JXF]set_uart_baudrate is failed\n");
return -1;
}
printf("[JXF]uart init is successful\n");
struct follow_camera_s tx_pkg = {};
orb_advert_t _follow_camera_tx_pub = NULL;
_follow_camera_tx_pub = orb_advertise(ORB_ID(follow_camera),&tx_pkg);//订阅一个话题,用于将获取到的角度数据发布出去
while(true){
if(write(uart_read,senddata,8) > 0)//向串口发送数据,参数分别是1、设备句柄 2、要发送的数据 3、要发送的数据长度
{
printf("write first successful\n");//通过nsh打印一些提示信息
if(read(uart_read,buffer,54) > 0)//读取串口数据到buffer中,参数很容易看出分别对应什么
{
printf("read first successful\n");
if(write(uart_read,senddata,8) > 0)
{
printf("write second successful\n");
if(read(uart_read,&buffer[54],54) > 0)
{
printf("read second successful\n");
for(int i=0;i<54;i++)
{
for(int j=i;j<54;j++)
{
if(buffer[j+0]==0x55&&buffer[j+1]==0xaa&&buffer[j+2]==0xdc && buffer[j+3]==0x04
&& buffer[j+4]==0x00 && buffer[j+5]==0x02 && buffer[j+6]==0x06 && buffer[j+7]==0x55 && buffer[j+8]==0xaa
&& buffer[j+9]==0xdc && buffer[j+10] == 0xec && buffer[j+11]==0x40)
{
x = (buffer[j+37]<<8|buffer[j+38])*0.00549;
y = (buffer[j+39]<<8|buffer[j+40])*0.00549;
tx_pkg.x = x;
tx_pkg.y = y;
tx_pkg.timestamp = hrt_absolute_time();
orb_publish(ORB_ID(follow_camera), _follow_camera_tx_pub,&tx_pkg);//将角度数据发布出去
printf("%f ",x);
printf("%f ",y);
printf("\n");
}
}
}
}
}
}
}
usleep(8 * 1000);
}
return 0;
}
总结:串口读写程序其实也很简单,主要步骤是
1、用open函数打开对饮的串口设备
2、设置波特率
3、通过write和read函数实现串口的读写
以上是串口的读写程序,但是要想在nsh中作为一个独立的程序运行,还要配置文件的支持,下面列出需要修改的文件:
1、在src/modules/中新建rw_uart文件夹,在文件夹中新建CMakeLists.txt文件(该文件的具体作用是什么这里就不仔细讲了)
2、CMakeLists.txt文件中的内容:
set(MODULE_CFLAGS)
px4_add_module(
MODULE modules__rw_uart
MAIN rw_uart
COMPILE_FLAGS
-Os
SRCS
rw_uart.c
)
3、新建rw_uart.c文件作为串口读写的主文件,并将以上的串口读写程序复制进去
4、修改boards/px4/fmu-v3/default.cmake文件,在MODULES最后添加rw_uart,文件结构如下:
MODULES
airspeed_selector
attitude_estimator_q
battery_status
camera_feedback
commander
dataman
ekf2
esc_battery
events
flight_mode_manager
fw_att_control
fw_pos_control_l1
gyro_calibration
gyro_fft
land_detector
landing_target_estimator
load_mon
local_position_estimator
logger
mavlink
mc_att_control
mc_hover_thrust_estimator
mc_pos_control
mc_rate_control
#micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih
temperature_compensation
uuv_att_control
uuv_pos_control
vmount
vtol_att_control
rw_uart
5、重新编译就可以在nsh看到对应的rw_uart程序了,运行即可。要想在启动时自动运行,就要在启动脚本rcS中添加对应的脚本