PX4无人机|MID360使用FAST_LIO,实现自主飞行及定点——PX4无人机配置流程(六)

PX4无人机|MID360使用FAST_LIO,实现自主飞行及定点——PX4无人机配置流程(六)

PX4固件版本为1.15.4

qgc地面站版本为4.4.5

飞控,使用微空科技MicoAir743V2

机载电脑:12代i5,ubuntu20.04

安装位置:mid360的接口对应飞机的后方

推荐阅读px4+vio实现无人机室内定位_px4+室内视觉定位-ZEEKLOG博客

和飞控连接机载电脑相关,有用

代码参考:

PX4|基于FAST-LIO mid360的无人机室内自主定位及定点悬停_fastlio mid360-ZEEKLOG博客
使用视觉或动作捕捉系统进行位置估计 | PX4 指南(主) --- Using Vision or Motion Capture Systems for Position Estimation | PX4 Guide (main)

一.px4飞控设置

建议看官方文档:Using Vision or Motion Capture Systems for Position Estimation | PX4 Guide (main)

1.将px4定位数据源设置为vinsion

参数EKF2_EV_CTRL:可以默认,或者看参数手册按需配置(该教程默认)Parameter Reference | PX4 Guide (main)



EKF2_HGT_REF参数:Vision 

 2.关闭罗盘:

教程:
PX4 | 无人机关闭磁力计罗盘飞行(yaw estimate error报错解决方法)-ZEEKLOG博客

需要注意的是,你现在走完上面飞控的设置,机头上电后会指向北。但在走完下面的程序后,你会发现上电后无人机机头指向东方(罗盘已经被关了)如下图所示

此外,加一个激光测距融合好处多多

二、程序

注意,下面我把雷达等频率改到了30HZ,但是在这频率下,定位精度实测只能有10hz的60%不到,慎重选择是否改频率!!!!!

1.代码

接下来创建发布 /mavros/vision_pose/pose 话题的功能包过程了

这里只提供代码,具体创建工作空间和功能包的步骤建议问AI

主要功能:将转化后的位姿信息以话题 /mavros/vision_pose/pose 发布。

#!/usr/bin/python3 #上面的python3不一定是这样写,建议找ai优化一下代码,和前面的推荐文章里的CPP代码其实一样的,该代码发布频率不太对 import rospy from nav_msgs.msg import Odometry from geometry_msgs.msg import PoseStamped import tf import numpy as np from collections import deque import math # 滑动窗口平均类,用于平滑 yaw 值 class SlidingWindowAverage: def __init__(self, window_size): self.window_size = window_size self.data_queue = deque() self.window_sum = 0.0 def add_data(self, new_data): # 如果新数据与上一个数据差异过大,重置队列 if self.data_queue and abs(new_data - self.data_queue[-1]) > 0.01: self.data_queue.clear() self.window_sum = 0.0 self.data_queue.append(new_data) self.window_sum += new_data # 如果队列大小超过窗口大小,移除最早的数据 if len(self.data_queue) > self.window_size: self.window_sum -= self.data_queue.popleft() return self.window_sum / len(self.data_queue) def get_size(self): return len(self.data_queue) def get_avg(self): if self.data_queue: return self.window_sum / len(self.data_queue) else: return 0.0 class FastLIOToMavros: def __init__(self): rospy.init_node('fastlio_to_mavros', anonymous=True) # 初始化位姿和四元数 self.p_lidar_body = np.zeros(3) self.q_mav = [0, 0, 0, 1] self.q_px4_odom = [0, 0, 0, 1] self.window_size = 8 self.swa = SlidingWindowAverage(self.window_size) self.init_flag = False self.init_q = tf.transformations.quaternion_from_euler(0, 0, 0) # 订阅 Fast-LIO 的 Odometry 数据 rospy.Subscriber('/Odometry', Odometry, self.vins_callback) # 订阅 PX4 的本地位置 Odometry 数据 rospy.Subscriber('/mavros/local_position/odom', Odometry, self.px4_odom_callback) # 发布视觉位姿数据到 PX4 self.vision_pub = rospy.Publisher('/mavros/vision_pose/pose', PoseStamped, queue_size=10) self.rate = rospy.Rate(30.0) self.run() def from_quaternion_to_yaw(self, q): # 将四元数转换为 yaw 角 euler = tf.transformations.euler_from_quaternion(q) return euler[2] def vins_callback(self, msg): # 获取 Fast-LIO 提供的位姿和四元数 self.p_lidar_body = np.array([ msg.pose.pose.position.x, msg.pose.pose.position.y, msg.pose.pose.position.z ]) self.q_mav = [ msg.pose.pose.orientation.x, msg.pose.pose.orientation.y, msg.pose.pose.orientation.z, msg.pose.pose.orientation.w ] def px4_odom_callback(self, msg): # 获取 PX4 的本地位置四元数,并计算 yaw 角 self.q_px4_odom = [ msg.pose.pose.orientation.x, msg.pose.pose.orientation.y, msg.pose.pose.orientation.z, msg.pose.pose.orientation.w ] yaw = self.from_quaternion_to_yaw(self.q_px4_odom) self.swa.add_data(yaw) def run(self): while not rospy.is_shutdown(): # 初始化 yaw 角 if self.swa.get_size() == self.window_size and not self.init_flag: init_yaw = self.swa.get_avg() self.init_q = tf.transformations.quaternion_from_euler(0, 0, init_yaw) self.init_flag = True if self.init_flag: # 旋转位姿以对齐初始 yaw 角 rot_matrix = tf.transformations.quaternion_matrix(self.init_q)[:3, :3] p_enu = np.dot(rot_matrix, self.p_lidar_body) # 构建并发布视觉位姿消息 vision = PoseStamped() vision.header.stamp = rospy.Time.now() vision.header.frame_id = "map" # 根据实际情况设置 vision.pose.position.x = p_enu[0] vision.pose.position.y = p_enu[1] vision.pose.position.z = p_enu[2] vision.pose.orientation.x = self.q_mav[0] vision.pose.orientation.y = self.q_mav[1] vision.pose.orientation.z = self.q_mav[2] vision.pose.orientation.w = self.q_mav[3] self.vision_pub.publish(vision) rospy.loginfo( "\nPosition in ENU:\n x: {:.3f}\n y: {:.3f}\n z: {:.3f}\nOrientation of LiDAR:\n x: {:.3f}\n y: {:.3f}\n z: {:.3f}\n w: {:.3f}".format( p_enu[0], p_enu[1], p_enu[2], self.q_mav[0], self.q_mav[1], self.q_mav[2], self.q_mav[3] ) ) self.rate.sleep() if __name__ == '__main__': try: FastLIOToMavros() except rospy.ROSInterruptException: pass 



自行创建fastlio_to_mavros节点的launch文件

2.运行mid360和fastlio的程序,修改雷达扫描频率

建议参考MID360+fastlio功能笔记-ZEEKLOG博客

按照官方说法 修改livox_ros_driver2 msg_MID360.launch ,使其频率达到30HZ(其实默认也能用)方法在livox_ros_driver2的github底下写了。

roslaunch livox_ros_driver2 msg_MID360.launch 在另一个终端中执行 roslaunch fast_lio mapping_mid360.launch

 输入下图指令查看是否修改了

3.运行mavros

安装步骤参考:mavros安装——解决疑难杂症- PX4无人机配置流程(三)-ZEEKLOG博客
 roslaunch mavros px4.launch

必须运行上面指令后马上运行下面的 fastlio_to_mavros 

4.运行自己创建的fastlio_to_mavros节点的launch文件

运行结果,和qgc里的画面(飞控通过数传和Windows电脑QGC连接,故而频率很低)


 

三、验证

推荐用官方的仿真来理解坐标系

你会发现一运行fastlio_to_mavros节点,无人机机头突然从指向北变成指向东方(确保罗盘已经被关了)

在Ubuntu上位机看输入rostopic echo /mavros/local_position/pose机头所指的方向为正X。X在前,Y朝向左,Z朝向下
打开qgc、点左上角Analyze Tools——>MAVlink检测,出现了LOCAL_POSITION_NED数据,坐标系看法如下:NED坐标系,X为北,Y为东,Z为下,机头指向东,那么向东运动(机头方向),Y会增大。向北运动(飞机左方向),X会增大。那么向上运动,Z会是负数,且越来越负。

实机向前方运动

会发现 QGC的LOCAL_POSITION_NED的Y增大

/mavros/local_position/pose的X增大

实机向右方运动

会发现 QGC的LOCAL_POSITION_NED的X变小为负数

/mavros/local_position/pose的Y变小为负数

当飞机向上运动

会发现 QGC的LOCAL_POSITION_NED的Z变成负数并且不断减小

实机建议调好pid再起飞,本人只试过定点飞行,没有任何问题

Read more

高飞团队新作!基于高阶CBF的端到端无人机,实现7.5m/s丛林穿越,突破RL安全瓶颈

高飞团队新作!基于高阶CBF的端到端无人机,实现7.5m/s丛林穿越,突破RL安全瓶颈

「强化学习高速避障新范式」 目录 01  主要方法  1. 训练阶段:基于物理先验的奖励塑形 1. Dijkstra全局引导奖励 2. 基于控制障碍函数的安全惩罚  2. 部署阶段:基于高阶控制障碍函数的实时滤波 02  实验结果  1.仿真训练与消融实验  2.基准测试  3.实机飞行验证 03  总结 在无人机高速避障领域,Ego-Planner等传统的模块化规划方法受限于感知-规划-控制的累积延迟,往往难以兼顾高速与安全;而RL等纯端到端的强化学习虽然敏捷,却因缺乏理论上的安全保障而被视为黑盒。 浙江大学高飞老师团队的这项工作,最令人振奋之处在于巧妙地构建了一套混合架构。 * 在训练阶段,利用 Dijkstra 势场 引导 RL 智能体跳出局部极小值陷阱 ,实现了全局可达性; * 在部署阶段,则引入了基于 高阶控制障碍函数(HOCBF)的安全滤波器,将神经网络输出的动作实时投影到可行域内。 这种设计不仅在数学上给出了碰撞避免的严谨证明,更在实测中实现了高达 7.5m/s

【硬核实战】Mac mini M4 部署 OpenClaw + Ollama 本地大模型:从零到一打通飞书机器人

【硬核实战】Mac mini M4 部署 OpenClaw + Ollama 本地大模型:从零到一打通飞书机器人

文章目录 * 一、 核心环境准备 * 二、 避坑指南:环境初始化在 Mac 终端部署时,首要解决的是权限与路径问题。 * 1. 终端常用快捷键* `Control + C`:强制停止当前运行的命令(如安装卡死时)。 * 2. Node.js 环境修复若遇到 `zsh: command not found: openclaw`,说明 NVM 路径未加载。 * 3. 临时加载环境 * 4. 永久写入配置 * 三、 模型选择:M4 性能调优 * 四、 OpenClaw 配置手术 (JSON 详解) * 五、 飞书机器人接入:最后的临门一脚 * 六、 运行与调试 * 启动 Gateway * 第一次发消息需授权 (Pairing) * 💡 结语

从零开发 AR 演讲提词器:基于 Rokid CXR-M SDK 的实战指南

从零开发 AR 演讲提词器:基于 Rokid CXR-M SDK 的实战指南

从零开发 AR 演讲提词器:基于 Rokid CXR-M SDK 的实战指南 站在讲台上,数百双眼睛注视着你。你开始演讲,却发现关键时刻想不起下一句要说什么——这种场景,每个演讲者都不陌生。 传统的解决方案是在讲台上放一张稿子,或者用 PPT 做备注。但低头看稿显得不专业,看 PPT 又要扭头,容易打断演讲节奏。如果能有一个只有自己能看到的"隐形提词器",演讲就能更加从容自信。 Rokid AR 眼镜恰好提供了这种可能:将提词内容无线传输到眼镜显示屏,演讲者只需自然平视,文字便清晰呈现,而台下观众毫无察觉。本文将完整记录如何利用 Rokid CXR-M SDK 从零开发这款演讲提词器应用。 一、技术方案设计 1.1 为什么选择 AR 眼镜 在确定技术方案前,我们先对比几种提词方案: 方案