PX4-Autopilot的串口读写驱动程序开发

2023-05-16

最近突然感觉,能把开发程序的流程写清楚比开发程序本身还困难,所以之前写的文章都是毫无章法,想到哪写到哪,努力改变中。。。

之前开发了超声波测量距离的驱动,实质是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 <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>

#include <uORB/topics/follow_camera.h>
#include <px4_platform_common/time.h>



#include <stdio.h>
#include <poll.h>
#include <string.h>
#include <math.h>
#include <stdlib.h>



#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/posix.h>

#include <poll.h>
#include <math.h>
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h> //引入 需要订阅sensor_combined 消息头文件
#include <uORB/topics/vehicle_attitude.h> //引入 需要发布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中添加对应的脚本

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

PX4-Autopilot的串口读写驱动程序开发 的相关文章

  • 【2020-8-9】APM,PX4,GAZEBO,MAVLINK,MAVROS,ROS之间的关系以及科研设备选型

    0 概述 无人机自主飞行平台可以分为四个部分 xff1a 动力平台 xff0c 飞行控制器 xff0c 机载电脑和模拟平台 动力平台 xff1a 负责执行飞行任务 xff0c 包括螺旋桨 电机 机架等 xff0c 用于科研的一般都是F380
  • px4: v2的主板刷写v2的固件

    v2的主板刷写v2的固件 fengxuewei 64 fengxuewei Legion Y7000 2019 PG0 src Firmware changwei rc span class token function make span
  • PX4 SITL Gazebo 仿真时 libgazebo_multirotor_base_plugin 插件运行时出错

    PX4 SITL Gazebo 仿真时 libgazebo multirotor base plugin 插件运行时出错 问题描述原因分析解决办法总结 问题描述 在 Gazebo 中进行 PX4 的软件在环仿真时 xff0c 执 make
  • PX4位置控制offboard模式说明

    offboard模式的开发及应用 一 px4固件的模式 px4固件支持10几种飞行模式 xff0c 从代码结构上分析 xff0c 分为基本模式 自定义模式和自定义子模式 1 基本模式 基本模式又分为 xff0c 位置控制模式 自稳模式 手动
  • Ubuntu18.04安装PX4踩坑、报错及解决方案整理

    笔者最近需要跑无人机巡检大坝的仿真 xff0c 于是在自己的Ubuntu2018 04中开始安装PX4 xff0c 问过不少之前已经装过PX4的师兄和同学 xff0c 都曾在PX4安装过程中踩过许多坑 xff0c 耗费了不少时间 xff0c
  • 飞行机器人(七)仿真平台XTDrone + PX4编译

    0 编译PX4固件 参考仿真平台基础配置教程 xff08 中文详细教程 xff09 仿真平台基础配置 语雀 yuque com https www yuque com xtdrone manual cn basic config 按照教程
  • PX4+Offboard模式+代码控制无人机起飞(Gazebo)

    参考PX4自动驾驶用户指南 https docs px4 io main zh ros mavros offboard cpp html 我的另一篇博客写了 键盘控制PX4无人机飞行 PX4无人机 键盘控制飞行代码 可以先借鉴本篇博客 xf
  • PX4 ---- Mixer

    文章目录 Mixer 混合控制 作用输入输出装载混控文件MAVROS代码解析总结示例MAINAUX Mixer 混合控制 作用 经过位置控制和姿态控制后 xff0c 控制量通过 actuator controls发布 xff0c 其中 co
  • PX4 ---- Indoor Flight

    文章目录 室内飞行ROS amp PX4Pose Data 飞机配置MAVROS 基于工训赛 VIO 飞行总结 室内飞行 ROS amp PX4 Pose Data 飞机配置 VIO 参考此处 xff0c 采用 T265 配置 相机与飞控机
  • PX4模块设计之一:SITL & HITL模拟框架

    PX4模块设计之一 xff1a SITL amp HITL模拟框架 1 模拟框架1 1 SITL模拟框架1 2 HITL模拟框架 2 模拟器类型3 MAVLink API4 总结 基于PX4开源软件框架简明简介的框架设计 xff0c 逐步分
  • PX4模块设计之五:自定义MAVLink消息

    PX4模块设计之五 xff1a 自定义MAVLink消息 1 MAVLink Dialects1 1 PX4 Dialects1 2 Paprazzi Dialects1 3 MAVLink XML File Format 2 添加自定义M
  • PX4模块设计之二十一:uORB消息管理模块

    PX4模块设计之二十一 xff1a uORB消息管理模块 1 uORB模块构建模式2 uORB消息管理函数2 1 状态查询2 2 资源利用2 3 模块启动2 4 模块停止3 uORB消息接口3 1 消息主题注册3 2 消息主题去注册3 3
  • PX4模块设计之二十三:自定义FlightTask

    PX4模块设计之二十三 xff1a 自定义FlightTask Step1 创建飞行模式文件夹Step2 创建飞行模式源代码和CMakeLists txt文件Step3 更新CMakeLists txt文件Step4 更新FlightTas
  • PX4模块设计之三十三:Sensors模块

    PX4模块设计之三十三 xff1a Sensors模块 1 Sensors模块简介2 模块入口函数2 1 主入口sensors main2 2 自定义子命令custom command2 3 模块状态print status 重载 3 Se
  • PX4模块设计之三十六:MulticopterPositionControl模块

    PX4模块设计之三十六 xff1a MulticopterPositionControl模块 1 MulticopterPositionControl模块简介2 模块入口函数2 1 主入口mc pos control main2 2 自定义
  • PX4模块设计之四十五:param模块

    PX4模块设计之四十五 xff1a param模块 1 param模块简介2 模块入口函数param main3 重要函数列表4 总结5 参考资料 1 param模块简介 Description Command to access and
  • mavros连接px4失败的usb-ttl原因

    问题描述 xff1a 最近在搞mavros xff0c 以方便协处理器和pixhawk通讯 xff0c 在按照官网教程安装mavros xff0c 设置px4 xff0c 连接硬件之后发现mavros卡在中间下不去 xff1a MAVROS
  • px4_simple_example和uorb机制

    px4 simple app PX4 Autopilot src exampes px4 simple app xff0c 这个程序是用c语言调用orb API和poll机制订阅和发布通讯数据 xff0c 但是这个例子并不是既有接收又有发送
  • PX4软件在环仿真注意点

    注 xff1a 最新内容参考PX4 user guide 点击此处 PX4下载指定版本代码和刷固件的三种方式 点击此处 PX4sitl固件编译方法 点击此处 PX4开发指南 点击此处 PX4无人机仿真 Gazebo 点击此处 px4仿真 知
  • PX4——Range Finder 篇

    Range Finder 此处选用的是 Benewake 下的 Lidar 参数设置 General Configuration 除了官方的参数设置外 xff0c 我在 EKF2 中还找到了 EKF2 RNG AID 参数 xff0c 用来

随机推荐

  • Linux 内核观测技术BPF

    BPF简介 BPF xff0c 全称是Berkeley Packet Filter xff08 伯克利数据包过滤器 xff09 的缩写 其诞生于1992年 xff0c 最初的目的是提升网络包过滤工具的性能 后面 xff0c 随着这个工具重新
  • bpftrace 指南

    文章目录 0 bpftrace0 1 bpftrace组件0 2 bpftrace 帮助信息0 3 bpftrace 工具速览表0 4 bpftrace 探针0 4 1 tracepoint0 4 2 usdt0 4 3 kprobe和kr
  • make px4_sitl_default gazebo编译报错解决办法

    PX4无人机ROS下仿真 xff0c 下载Fireware后执行make px4 sitl default gazebo编译 xff0c 编译过程中出现如下错误 xff1a 错误原因是两个package没有安装 xff1a gstreame
  • 理解实时操作系统与裸机的区别

    早期嵌入式开发没有嵌入式操作系统的概念 xff0c 直接操作裸机 xff0c 在裸机上写程序 xff0c 比如用51单片机基本就没有操作系统的概念 通常把程序分为两部分 xff1a 前台系统和后台系统 简单的小系统通常是前后台系统 xff0
  • 4.1.2.HTTP报文格式解析

    不同的请求方式 xff0c 他们的请求格式可能是不一样的 xff0c 请求格式就是我们所说的的报文格式 但是 xff0c 通常来说一个HTTP请求报文由请求行 xff08 request line xff09 请求头 xff08 heade
  • apt-get autoremove 命令你敢不敢用?

    apt get autoremove 命令你敢不敢用 xff1f 用apt时看到有提示 xff0c 说有些软件包已经不再被需要 xff0c 可以使用 autoremove 命令删除 xff0c 我是一个希望保持系统简洁性的人 xff0c 当
  • 英伟达(NVIDIA)系列显卡(GPU)技术指标对比排行

    性能概览 关于N卡架构发展史详见本人前篇博客 点击打开链接 Pascal xff08 帕斯卡 xff09 架构 显卡名称cuda核心数量主频 xff08 MHz xff09 超频 xff08 MHz xff09 存储速度显存配置位宽带宽 G
  • Cmake gcc make makefile 区别以及联系

    作者 xff1a 辉常哥 链接 xff1a https www zhihu com question 27455963 answer 89770919 来源 xff1a 知乎 著作权归作者所有 商业转载请联系作者获得授权 xff0c 非商业
  • 使用Docker构建一个Git镜像,用来clone仓库

    概述 使用docker已经有一年多了 xff0c 最近意识到 xff0c 我在快速编排服务的时候 xff0c shell脚本里用到的git还是原生的 于是打算也将git容器化 xff0c 在dockerhub上搜罗了一筐 xff0c 找到这
  • make -C M选项

    modules MAKE C KERNELDIR M 61 PWD modules 这句是Makefile的规则 xff1a 这里的 MAKE 就相当于make xff0c C 选项的作用是指将当前工作目录转移到你所指定的位置 M 61 选
  • 什么是耦合、解耦

    一 耦合 1 耦合是指两个或两个以上的体系或两种运动形式间通过相互作用而彼此影响以至联合起来的现象 2 在软件工程中 xff0c 对象之间的耦合度就是对象之间的依赖性 对象之间的耦合越高 xff0c 维护成本越高 xff0c 因此对象的设计
  • ERROR! Session/line number was not unique in database. History logging moved to new session 178

    原来的代码 xff1a MODEL NAME 61 39 ssd mobilenet v1 coco 2017 11 17 39 载入训练好的pb模型 detection graph 61 tf Graph with detection g
  • 基于px4的hc-sr04-pwm超声波模块的驱动开发

    一直想实现无人的避障功能 xff0c 但是px4源生代码又不支持避障 xff0c 所以只能自己动手写 避障的基础条件还是获取距离数据 xff0c 超声波模块就是最熟悉也是最简单的模块了 px4源生代码也支持了几种超声波模块 xff0c 但是
  • px4最新版commander代码分析

    commander位于Firmware src modules commander文件夹中 该部分主要负责对地面站 遥控器以及其它部分发布的cmd命令 xff0c 包括vehicle command VEHICLE CMD DO SET M
  • SMPL模型进阶

    SMPL模型是一种参数化人体模型 xff0c 是马普所提出的一种人体建模方法 xff0c 该方法可以进行任意的人体建模和动画驱动 这种方法与传统的LBS的最大的不同在于其提出的人体姿态影像体表形貌的方法 xff0c 这种方法可以模拟人的肌肉
  • px4最新版navigation代码分析

    navigation部分位于代码Firmware navigator文件夹中 其中不仅仅包含navigator的代码 xff0c 最主要的9种不同的飞行模式的代码 xff0c 它们针对不同的飞行模式计算出不同的期望的位置 xff0c 即po
  • 基于最新版本px4的takeoff代码分析

    takeoff是px4的一种飞行模式 xff0c 跟之前分析的lotier部分是一种类型 takeoff模式也是由navigator部分进行调用的 xff0c 所以也就印证了上一篇说navigator相当于一个分发器的说法 各种飞行模式实际
  • Nuttx移植到S5PV210

    最近没有分析飞控的代码 xff0c 转而研究Nuttx实时操作系统的移植 入门一个操作的移植还是挺有难度的 xff0c 首先代码的框架能理清楚就很不容易了 xff0c 尤其是Nuttx这种相对小众的操作系统 xff0c 参考资料比较少 xf
  • 基于最新版PX4-Autopilot的follow_target代码分析

    快有半年没更博客了 最近加班比较多 xff0c 而且一直想研究研究ROS那块 xff0c 但是学到的又不足以写出博客 xff0c 也就一直没更新 最近接了一个目标跟踪的二次开发的活 xff0c 需求就是根据挂载摄像头传回来的与识别的目标的角
  • PX4-Autopilot的串口读写驱动程序开发

    最近突然感觉 xff0c 能把开发程序的流程写清楚比开发程序本身还困难 xff0c 所以之前写的文章都是毫无章法 xff0c 想到哪写到哪 xff0c 努力改变中 之前开发了超声波测量距离的驱动 xff0c 实质是px4的IO口操作 本次的