树莓派与pixhawk串口通信

article/2025/9/29 6:24:03

一、Pixhawk部分

1.读取数据测试

步骤:
  • 在Firmware/src/modules中添加一个新的文件夹,命名为rw_uart
  • 在rw_uart文件夹中创建CMakeLists.txt文件,并输入以下内容:
px4_add_module(MODULE modules__rw_uartMAIN rw_uartCOMPILE_FLAGS-OsSRCSrw_uart.cDEPENDSplatforms__common
)
  • 在rw_uart文件夹中创建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;
}
  • 注册新添加的应用到NuttShell中。/src/Firmware/cmake/configs/nuttx_px4fmu-v2_default.cmake文件中添加如下内容:
modules/rw_uart
  • 编译并刷固件
make clean
make px4fmu-v2_default

2.定义和发布主题

2.1 新建主题

  • msg文件夹下新建rw_uart_raspberry_topic.msg文件
 char[4] datastr0 uint8 data 
  • 在msg文件夹中的CMakeList文件中加入
rw_uart_raspberry_topic.msg

在这里插入图片描述

2.2 补充修改rw_uart.c文件

  • rw_uart.c
#include <stdio.h>
#include <termios.h>
#include <unistd.h>
#include <stdbool.h>
#include <errno.h>
#include <drivers/drv_hrt.h>
#include <uORB/topics/rw_uart_raspberry_topic.h>
#include <uORB/uORB.h>
#include <string.h>
#include <systemlib/err.h>
#include <systemlib/systemlib.h>
#include <fcntl.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <sys/ioctl.h>
#include <px4_tasks.h>static bool thread_should_exit = false;
static bool thread_running = false;
static int daemon_task;__EXPORT int rw_uart_main(int argc, char *argv[]);
int rw_uart_thread_main(int argc, char *argv[]);static void usage(const char *reason);
static int uart_init(char * uart_name);
static int set_uart_baudrate(const int fd, unsigned int baud);static void usage(const char *reason)
{if (reason) {fprintf(stderr, "%s\n", reason);}fprintf(stderr, "usage: position_estimator_inav {start|stop|status} [param]\n\n");exit(1);
}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 uart_init(char * uart_name)
{int serial_fd = open(uart_name, O_RDWR | O_NOCTTY);if (serial_fd < 0) {err(1, "failed to open port: %s", uart_name);return false;}return serial_fd;
}int rw_uart_main(int argc, char *argv[])
{if (argc < 2) {usage("[YCM]missing command");}if (!strcmp(argv[1], "start")) {if (thread_running) {warnx("[YCM]already running\n");return 0;}thread_should_exit = false;daemon_task = px4_task_spawn_cmd("rw_uart",SCHED_DEFAULT,SCHED_PRIORITY_DEFAULT,2000,rw_uart_thread_main,(argv) ? (char * const *)&argv[2] : (char * const *)NULL);return 0;}if (!strcmp(argv[1], "stop")) {thread_should_exit = true;return 0;}if (!strcmp(argv[1], "status")) {if (thread_running) {warnx("[YCM]running");} else {warnx("[YCM]stopped");}return 0;}usage("unrecognized command");return 1;
}
int rw_uart_thread_main(int argc, char *argv[])
{warnx("[daemon] starting\n");thread_running = true;char data = '0';char buffer[4] = "";/** 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/ttyS2");if(false == uart_read)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");struct rw_uart_raspberry_topic_s test_data; //定义类型为rw_uart_raspberry_topic_s的结构体变量rdorb_advert_t rw_uart_raspberry_topic_pub = orb_advertise(ORB_ID(rw_uart_raspberry_topic), &test_data);while(!thread_should_exit){read(uart_read,&data,1);if(data == 'R'){for(int i = 0;i <4;++i){read(uart_read,&data,1); //读取串口设备数据1个字节,放到data中buffer[i] = data;data = '0';}write(uart_read,&buffer,4);char * s;strncpy(test_data.datastr0,buffer,4);test_data.data = strtol(test_data.datastr0,&s,10);orb_publish(ORB_ID(rw_uart_raspberry_topic), rw_uart_raspberry_topic_pub, &test_data);int b=strtol(test_data.datastr0,&s,10);printf("\t%s\t%d\t%d\n",test_data.datastr0,test_data.data,b);}}warnx("[YCM]exiting");thread_running = false;close(uart_read);fflush(stdout);return 0;
}

2.3设置自启动

  • 在ROMFS/px4fmu_common/init.d/rcS中添加自启动
rw_uart start
  • 编译并刷固件
make clean
make px4fmu-v2_default
make px4fmu-v2_default_upload

二、Raspberry部分

  • 循环发送’R1100’小程序(python)
# -*- coding: utf-8 -*-
import serial
import timedef port_send(send_date):if (serial.isOpen()):serial.write(send_date.encode('utf-8'))time.sleep(0.5)else:print("send failed")if __name__ == "__main__":serial = serial.Serial('/dev/ttyS2', 9600, timeout=0.5)  # /dev/ttyUSB0if serial.isOpen():print("open success")else:print("open failed")while True:port_send("R1100")

三、Pixhawk与树莓派连接

  • TX—RX
  • RX—TX
  • GND—GND
    在这里插入图片描述
    在这里插入图片描述
  • TELEM2从左到右分别是VC TXD RXD 未知 未知 GND

测试结果:
在这里插入图片描述

四、编译过程中产生的问题

在编译的过程中碰到了很多问题,但是大部分都是可以百度谷歌到的。我主要将不能搜索到的问题摆出来,供大家在开发过程时参考。

  • implicit declaration of function ‘px4_task_spawn_cmd’
    在这里插入图片描述
    问题原因及解决方案:
    缺失相关的头文件,补充头文件:
#include <px4_tasks.h>
  • compilation terminated due to -Wfatal -errors
    在这里插入图片描述
    问题原因及解决方案:
    对应函数‘set_uart_baudrate’格式不对
    删除对应函数,重新书写函数。

参考资料

Pixhawk与树莓派3的串口通信
Pixhawk—通过串口方式添加一个自定义传感器(超声波为例)
pixhawk串口读取传感器数据
Python 串口读写实现


http://chatgpt.dhexx.cn/article/JIBAEqkf.shtml

相关文章

【四旋翼】pixhawk2.4.8-地面站配置-APM固件-四旋翼从装机到试飞

文章目录 整体流程图&#xff1a;相关网址汇总&#xff1a;入门常识&#xff1a;一、硬件准备二、软件准备1 已实飞测试2 MP地面站 任意版本下载&#xff1a;3 APM固件 任意版本下载&#xff1a; 三、飞控校准1 刷固件2 机架选择3 加速度计校准4 指南针校准5 遥控器校准6 飞行模…

TFmini Plus 在开源飞控 pixhawk 上的应用

TFmini Plus 在开源飞控 pixhawk 上的应用 TFmini Plus 可以直接连接 Pixhawk 的串口使用。飞行器可以使用 TFmini Plus 来实现定高或 者避障功能。本文档适用于 pixhawk ArduCopter V3.6.2 或更高版固件(注:雷达在 V3.6.2 及以上 固件使用标准输出格式即可,无需使用 PIX 模…

Windows下的pixhawk环境搭建

官网详细介绍&#xff1a;http://ardupilot.org/dev/docs/editing-the-code-with-eclipse.html 提示&#xff1a;GitHub没有写使用过程&#xff0c;如何而简历仓库。具体网上有教程&#xff0c;如果英语好可以去官网自行翻译&#xff0c;安装适合自己操作系统的开发环境&#…

Pixhawk参数调整

Pixhawk copter固件的默认参数是为3DR QUAD COPTER设计的。如果你想获得一个最佳的飞行表现的话。你需要对一些参数做一些调整。调整的参数主要是Extended Tuning下面的Roll和Pitch的PID,来获得稳定的姿态。 在copter的参数调整里边比较重要的参数主要是Roll、Pitch、yaw、…

飞控pixhawk硬件框架

本文转载于&#xff1a;https://blog.csdn.net/csshuke/article/details/78952026 &#xfeff;&#xfeff; 1.Phxhawk连接线路 2.Phxhawk硬件芯片列表 处理器 STM32F427 VIT6 (168 Mhz/256 KB RAM/2 MB 闪存 100Pin)32位 STM32F100C8T6 &#xff08;48Pin&#xff09;故障保…

Pixhawk的历史

发展历程&#xff1a;APM-->PX4FMU/IO-->Pixhawk&#xff1a; 1、Arduino简介 Arduino就是主要以以AVR单片机为核心控制器的单片机应用开发板&#xff08;当然也有其他核心的例如STM32版本的但是不是官方的&#xff0c;还有intel的伽利略&#xff09;&#xff0c;或者是学…

pixhawk 学习笔记

1.pixhawk4硬件&#xff1a; Main FMU Processor: STM32F765 32 Bit Arm Cortex-M7, 216MHz, 2MB memory, 512KB RAMIO Processor: STM32F100 32 Bit Arm Cortex-M3, 24MHz, 8KB SRAMOn-board sensors: Accel/Gyro: ICM-20689Accel/Gyro: BMI055Magnetometer: IST8310Baromete…

pixhawk计算机无法识别,PIXHAWK教程 3.1.2 连接你的遥控输入和电机(Pixhawk)

连接你的遥控输入和电机(Pixhawk) 目录 连接你的遥控输入和电机(Pixhawk) 连接蜂鸣器和安全开关 连接其他外部设备 连接遥控输入 连接电机输入 安装螺旋桨 顺时针和逆时针桨的识别 连接蜂鸣器和安全开关 蜂鸣器和安全开关依附于Pixhawk。 分别连接到蜂鸣器和开关端口。 连接其他…

pixhawk连接到nvidia xavier

实物是bluerov。固件是ardusub, https://www.ardusub.com/ 上图中右下角蓝usb一端接pixhawk&#xff0c;另外一端接xavier。xavier上运行 $ls /dev/ttyA* 会增加设备/dev/ttyACM0 在xavier端安装好各种mavlink mavproxy 软件包。 $ xargs -a "/home/pcl/mavproxy…

Pixhawk6c编译

以前一直用pixhawk4以及4mini&#xff0c;版本1.11&#xff0c;这两款目前停产&#xff0c;6x也快停产&#xff0c;没什么货源了。只能试试6c。 一&#xff1a;下载 流程&#xff1a;按照官网的流程&#xff0c;先git clone 输入&#xff1a; git clone https://github.com/…

pixhawk使用WiFi模块

pixhawk使用WiFi 前期准备刷固件安装刷固件软件进入刷固件模式下载固件刷固件 使用接线飞控参数更改使用方法 在使用pixhawk的时候有时候在无人机上不方便搭载处理器&#xff0c;这个时候进行外部控制。或者QGC有线方式连接无人机不方便的时候就需要通过WiFi来连接了。 使用ESP…

pixhawk学习

原文转载至https://blog.csdn.net/u013181595/article/details/80976610 1硬件架构分析 Pixhawk是一款基于ARM芯片的32位开源飞控&#xff0c;由ETH的computer vision and geometry group的博士生Lorenz Meier开发。最初采用的是分体式的设计即px4&#xff08;由px4fmu和px4io…

使用者——初见Pixhawk

是什么 Pixhawk简单介绍 直接使用二次开发 Pixhawk总体概述怎么用 Pixhawk初次使用 搭建调试环境初始化配置测试试飞调整参数提高性能 &#xff08;是什么) Pixhawk简单介绍 PixHawk是著名飞控厂商3DR推出的新一代独立、开源、高效的飞行控制器&#xff0c;前身为APM飞控&…

Pixhawk基础—认识Pixhawk

Pixhawk简介 pixhawk是由3DR联合APM小组与PX4小组于2014年推出的飞控PX4的升级版&#xff0c;它同时拥有PX4和APM两套固件和相应的地面站软件。该飞控是目前全世界飞控产品中硬件规格最高的产品。 Pixhawk基础 端口介绍 1、Spektrum DSM receiver(Spektrum DSM信号转换为PWM…

pixhawk入门知识

Pixhawk是一种先进的自动驾驶仪&#xff0c;由PX4开放硬件项目设计和3D机器人制造。它具有来自ST公司先进的处理器和传感器技术&#xff0c;以及NuttX实时操作系统&#xff0c;能够实现惊人的性能&#xff0c;灵活性和可靠性控制任何自主飞行器。Pixhawk旗舰版模块将伴随着新的…

实验室无人机平台 Pixhawk 2.4.8 / PX4 v1.9.2

实验室无人机平台及相关应用 无人机平台 目录 实验室无人机平台及相关应用无人机平台1. 硬件1.1 无人机本体1.1.1 四旋翼无人机机架1.1.2 Pixhawk 2.4.8 飞控板1.1.3 电调1.1.4 分电板1.1.5 锂电池1.1.6 电机1.1.7 遥控模块 1.2 机载电脑与传感器1.2.2 激光雷达1.2.3 双目相机…

Pixhawk系统架构介绍

前段时间导师叫我做扑翼无人机&#xff0c;工程上需要实现的&#xff0c;能够通过程控飞起来&#xff0c;感觉难度挺大。先从研究PX4开始&#xff0c;打算一步步理解透整个PX4的框架&#xff0c;机型的适配、旋翼、固定翼的姿态控制&#xff0c;新机型的添加等等。不知道能不能…

程序员的桌面壁纸

希望这些图片对你们有用。 ​​ 实用系列 Logo系列 你们最喜欢那一张图片

​企业要求程序员统一电脑桌面,网友:桌面壁纸都不配拥有?

在职场上经常会遇到一些奇葩的规定&#xff0c;相信不少人都遇到过&#xff0c;因为在公司打工&#xff0c;所以面对这些奇葩规定也是很无奈&#xff0c;只能选择妥协&#xff0c;那么大家都遇到过哪些奇葩的规定呢&#xff1f;最近就在职场论坛看到一个公司的奇葩规定。 一家…