PX4|基于FAST-LIO mid360的无人机室内自主定位及定点悬停

目录

  • 前言
  • 环境配置
  • 运行fast-lio
  • 修改px4位置信息融合方式
  • 编写位置坐标转换及传输节点

前言

在配置mid360运行环境后,可使用mid360进行室内的精准定位。

环境配置

在livox_ros_driver2的上级目录src下保存fast-lio的工程

git clone https://github.com/hku-mars/FAST_LIO.git
cd FAST_LIO
git submodule update --init

为使用mid360作为硬件输入修改源代码中的所有livox_ros_driverlivox_ros_driver2(包括.cpp .h 以及 package.xml)
livox_ros_driver2的pkg中编译

cd src/livox_ros_driver2/
./build ROS1

编译过程大概需要3g的内存,若机载板物理内存不足,需要增大swap大小增加交换空间,可参考增加swap解决。

运行fast-lio

执行下述指令时请确保mid360运行环境中的rviz可以成功显示环境点云信息。
执行以下指令

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

执行后使用rostopic list查看话题列表,出现/Odometry话题即为成功运行
在这里插入图片描述
使用

rostopic echo /Odometry

可以查看当前的定位定姿信息。
在这里插入图片描述

修改px4位置信息融合方式

这里使用光流以及激光定位信息。
修改EKF2_AID_MASK为10
在这里插入图片描述

编写位置坐标转换及传输节点

使用/mavros/vision_pose/pose话题将激光得到的定位信息传递至px4进行融合,需注意该话题的位置信息应建立在ENU坐标系下(MAVROS使用该坐标系作为惯性系),传递至px4接收时会自动转化为NED坐标系供EKF2进行融合。
因此需首先计算出初始化时fast-lio所产生的坐标系与ENU坐标系的旋转关系(主要为偏航角),并将该转换关系定为初始值

 init_q = Eigen::AngleAxisd(init_yaw,Eigen::Vector3d::UnitZ())//des.yaw
    * Eigen::AngleAxisd(0.0,Eigen::Vector3d::UnitY())
    * Eigen::AngleAxisd(0.0,Eigen::Vector3d::UnitX());

为减小初始偏航角误差,使用滑动窗口求平均值。

 class SlidingWindowAverage {
public:
    SlidingWindowAverage(int windowSize) : windowSize(windowSize), windowSum(0.0) {}

    double addData(double newData) {
        if(!dataQueue.empty()&&fabs(newData-dataQueue.back())>0.01){
            dataQueue = std::queue<double>();
            windowSum = 0.0;
            dataQueue.push(newData);
            windowSum += newData;
        }
        else{            
            dataQueue.push(newData);
            windowSum += newData;
        }

        // 如果队列大小超过窗口大小,弹出队列头部元素并更新窗口和队列和
        if (dataQueue.size() > windowSize) {
            windowSum -= dataQueue.front();
            dataQueue.pop();
        }
        windowAvg = windowSum / dataQueue.size();
        // 返回当前窗口内的平均值
        return windowAvg;
    }

    int get_size(){
        return dataQueue.size();
    }

    double get_avg(){
        return windowAvg;
    }

private:
    int windowSize;
    double windowSum;
    double windowAvg;
    std::queue<double> dataQueue;
};

求解得到较为准确的初始偏航角后,该偏航角可视为fast-lio位置信息所在坐标系与惯性系的旋转关系。
在不考虑机体中心与激光雷达中心位置平动的情况下,可以将位置信息直接进行坐标转换。

p_enu = init_q*p_lidar_body;

将转换后的位置信息通过/mavros/vision_pose/pose传递

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 = q_mav.x();
vision.pose.orientation.x = q_mav.x();
vision.pose.orientation.y = q_mav.y();
vision.pose.orientation.z = q_mav.z();
vision.pose.orientation.w = q_mav.w();

vision.header.stamp = ros::Time::now();
vision_pub.publish(vision);

分别执行以下节点
在这里插入图片描述
在QGC中可以查看LOCAL_POSITION_NED观察定位结果,静止时定位信息在3厘米以内漂移。
在这里插入图片描述
在调整好飞行时位置控制内外环的情况下,可以遥控起飞后切换至position模式,可以实现定点悬停。

位置转换的源码如下

#include <ros/ros.h>
#include <geometry_msgs/PoseStamped.h>
#include <nav_msgs/Odometry.h>
#include <Eigen/Eigen>
#include<cmath>
 #include <queue>
 
Eigen::Vector3d p_lidar_body, p_enu;
Eigen::Quaterniond q_mav;
Eigen::Quaterniond q_px4_odom;

 class SlidingWindowAverage {
public:
    SlidingWindowAverage(int windowSize) : windowSize(windowSize), windowSum(0.0) {}

    double addData(double newData) {
        if(!dataQueue.empty()&&fabs(newData-dataQueue.back())>0.01){
            dataQueue = std::queue<double>();
            windowSum = 0.0;
            dataQueue.push(newData);
            windowSum += newData;
        }
        else{            
            dataQueue.push(newData);
            windowSum += newData;
        }

        // 如果队列大小超过窗口大小,弹出队列头部元素并更新窗口和队列和
        if (dataQueue.size() > windowSize) {
            windowSum -= dataQueue.front();
            dataQueue.pop();
        }
        windowAvg = windowSum / dataQueue.size();
        // 返回当前窗口内的平均值
        return windowAvg;
    }

    int get_size(){
        return dataQueue.size();
    }

    double get_avg(){
        return windowAvg;
    }

private:
    int windowSize;
    double windowSum;
    double windowAvg;
    std::queue<double> dataQueue;
};

int windowSize = 8;
SlidingWindowAverage swa=SlidingWindowAverage(windowSize);

double fromQuaternion2yaw(Eigen::Quaterniond q)
{
  double yaw = atan2(2 * (q.x()*q.y() + q.w()*q.z()), q.w()*q.w() + q.x()*q.x() - q.y()*q.y() - q.z()*q.z());
  return yaw;
}

void vins_callback(const nav_msgs::Odometry::ConstPtr &msg)
{

    p_lidar_body = Eigen::Vector3d(msg->pose.pose.position.x, msg->pose.pose.position.y, msg->pose.pose.position.z);

    q_mav = Eigen::Quaterniond(msg->pose.pose.orientation.w, msg->pose.pose.orientation.x, msg->pose.pose.orientation.y, msg->pose.pose.orientation.z);
}
 
void px4_odom_callback(const nav_msgs::Odometry::ConstPtr &msg)
{
    q_px4_odom = Eigen::Quaterniond(msg->pose.pose.orientation.w, msg->pose.pose.orientation.x, msg->pose.pose.orientation.y, msg->pose.pose.orientation.z);
    swa.addData(fromQuaternion2yaw(q_px4_odom));
} 

int main(int argc, char **argv)
{
    ros::init(argc, argv, "vins_to_mavros");
    ros::NodeHandle nh("~");
 
    ros::Subscriber slam_sub = nh.subscribe<nav_msgs::Odometry>("/Odometry", 100, vins_callback);
    ros::Subscriber px4_odom_sub = nh.subscribe<nav_msgs::Odometry>("/mavros/local_position/odom", 5, px4_odom_callback);
 
    ros::Publisher vision_pub = nh.advertise<geometry_msgs::PoseStamped>("/mavros/vision_pose/pose", 10);
 
 
    // the setpoint publishing rate MUST be faster than 2Hz
    ros::Rate rate(20.0);
 
    ros::Time last_request = ros::Time::now();
    float init_yaw = 0.0;
    bool init_flag = 0;
    Eigen::Quaterniond init_q;
    while(ros::ok()){
        if(swa.get_size()==windowSize&&!init_flag){
            init_yaw = swa.get_avg();
            init_flag = 1;
            init_q = Eigen::AngleAxisd(init_yaw,Eigen::Vector3d::UnitZ())//des.yaw
    * Eigen::AngleAxisd(0.0,Eigen::Vector3d::UnitY())
    * Eigen::AngleAxisd(0.0,Eigen::Vector3d::UnitX());
        // delete swa;
        }

        if(init_flag){
            geometry_msgs::PoseStamped vision;
            p_enu = init_q*p_lidar_body;
    
            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 = q_mav.x();
            vision.pose.orientation.x = q_mav.x();
            vision.pose.orientation.y = q_mav.y();
            vision.pose.orientation.z = q_mav.z();
            vision.pose.orientation.w = q_mav.w();
    
            vision.header.stamp = ros::Time::now();
            vision_pub.publish(vision);
    
            ROS_INFO("\nposition in enu:\n   x: %.18f\n   y: %.18f\n   z: %.18f\norientation of lidar:\n   x: %.18f\n   y: %.18f\n   z: %.18f\n   w: %.18f", \
            p_enu[0],p_enu[1],p_enu[2],q_mav.x(),q_mav.y(),q_mav.z(),q_mav.w());

        }

 
        ros::spinOnce();
        rate.sleep();
    }
 
    return 0;
}

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.kler.cn/a/274714.html

如若内容造成侵权/违法违规/事实不符,请联系我们进行投诉反馈qq邮箱809451989@qq.com,一经查实,立即删除!

相关文章

AI短视频制作一本通:文本生成视频、图片生成视频、视频生成视频

第一部分&#xff1a;文本生成视频 1. 文本生成视频概述 随着人工智能&#xff08;AI&#xff09;技术的飞速发展&#xff0c;视频制作领域也迎来了创新的浪潮。文本生成视频是其中的一项令人激动的进展&#xff0c;它利用自然语言处理技术将文本内容转化为视频。这项技术在广…

redis和rabbitmq实现延时队列

redis和rabbitmq实现延时队列 延迟队列使用场景Redis中zset实现延时队列Rabbitmq实现延迟队列 延迟队列使用场景 1. 订单超时处理 延迟队列可以用于处理订单超时问题。当用户下单后&#xff0c;将订单信息放入延迟队列&#xff0c;并设置一定的超时时间。如果在超时时间内用户…

默写单词cpp(初学者版本)

笔摔坏了直接使用版:yum:仔细学习版:yum:1.直接使用版:yum:&#xff08;文件使用规范&#xff09;(1)文件(2)使用规范 2.仔细学习版。将会讲各个函数的功能和细节。今天太晚了&#xff0c;明天再写。 笔摔坏了 在一个阳光明媚的早晨&#xff0c;我愉快的奋笔疾书&#xff0c;抄…

基于VMware虚拟机安装MacOS BigSur系统

这周用VMWare搞了个MacOS虚拟机&#xff0c;也算是完成初中高中时候的梦想了吧~~&#xff08;那时候我的电脑配置还很拉跨&#xff0c;带不动虚拟机&#xff09;~~ 写一篇博客记录一下&#xff0c;当然这也是yonagi04.github.io建站的第一篇新博客 准备工作&#xff08;VMWare…

c++ 常用函数 集锦 整理中

c 常用函数集锦 目录 c 常用函数集锦 1、string和wstring之间转换 2、经纬度转 xyz 值 互转 3 、获取 根目录下的文件地址 1、string和wstring之间转换 std::string convertWStringToString(std::wstring wstr) {std::string str;if (!wstr.empty()){std::wstring_convert<…

31-Java前端控制器模式(Front Controller Pattern)

Java前端控制器模式 实现范例 前端控制器模式&#xff08;Front Controller Pattern&#xff09;是用来提供一个集中的请求处理机制&#xff0c;所有的请求都将由一个单一的处理程序处理该处理程序可以做认证/授权/记录日志&#xff0c;或者跟踪请求&#xff0c;然后把请求传给…

LabVIEW NV色心频率扫描

LabVIEW NV色心频率扫描 通过LabVIEW软件开发一个能够实现对金刚石氮空位&#xff08;Nitrogen-Vacancy&#xff0c;NV&#xff09;色心的频率扫描系统。系统通过USB协议与硬件设备通信&#xff0c;对NV色心进行高精度的频率扫描&#xff0c;满足了频率在2.6 GHz到3.2 GHz范围…

云原生:重塑未来应用的基石

随着数字化时代的不断深入&#xff0c;云原生已经成为了IT领域的热门话题。它代表着一种全新的软件开发和部署范式&#xff0c;旨在充分利用云计算的优势&#xff0c;并为企业带来更大的灵活性、可靠性和效率。今天我们就来聊一聊这个热门的话题&#xff1a;云原生~ &#x1f4…

DevEco Studio 项目创建

安装DevEco Studio后开始使用&#xff0c;双击桌面DevEco Studio 快捷方式弹出界面&#xff1a; 选择Application —> Empty Ability&#xff0c;点击Next 项目配置 Project name&#xff1a;工程的名称&#xff0c;可以自定义&#xff0c;由大小写字母、数字和下划线组成。…

解锁编程潜能:ChatGPT如何革新软件开发

目录 一、背景 二、功能描述 三、总结 一、背景 在这个飞速发展的数字时代&#xff0c;软件开发的效率和质量成了衡量一个开发者能力的重要标准。随着人工智能技术的不断进步&#xff0c;越来越多的开发者开始寻找能够提升工作效率的新方法。我就是其中之一&#xff0c;最近…

【RabbitMQ | 第一篇】消息队列基础知识

文章目录 1.消息队列基础知识1.1什么是消息队列&#xff1f;1.2消息队列有什么用&#xff1f;&#xff08;结合项目说&#xff09;1.2.1异步处理1.2.2削峰/限流1.2.3降低系统耦合性1.2.4实现分布式事务 1.3消息队列的缺点1.4JMS和AMQP1.4.1 JMS的两种消息模型&#xff08;1&…

海外社交营销为什么用云手机?不用普通手机?

海外社交营销作为企业拓展海外市场的重要手段&#xff0c;正日益受到企业的青睐。云手机以其成本效益和全球性特征&#xff0c;成为海外社交营销领域的得力助手。那么&#xff0c;究竟是什么特性使得越来越多的企业选择利用云手机进行海外社交营销呢&#xff1f;下文将对此进行…

【微服务】Gateway服务网关

文章目录 1、为什么需要网关2、gateway示例1&#xff09;创建gateway服务&#xff0c;引入依赖2&#xff09;编写启动类3&#xff09;基础配置和路由规则4&#xff09;重启测试5&#xff09;网关路由流程图6&#xff09;总结 3、断言工厂4、过滤器工厂4.1.路由过滤器的种类4.2、…

[Python人工智能] 四十三.命名实体识别 (4)利用bert4keras构建Bert+BiLSTM-CRF实体识别模型

从本专栏开始,作者正式研究Python深度学习、神经网络及人工智能相关知识。前文讲解如何实现中文命名实体识别研究,构建BiGRU-CRF模型实现。这篇文章将继续以中文语料为主,介绍融合Bert的实体识别研究,使用bert4keras和kears包来构建Bert+BiLSTM-CRF模型。然而,该代码最终结…

unity 学习笔记 4.坐标系

下载源码 UnityPackage 目录 1.基础知识 1.1.世界坐标和局部坐标 1.2.屏幕坐标 2.坐标系转换 3.练习&#xff1a;判断鼠标单击的位置 1.基础知识 1.1.世界坐标和局部坐标 1.2.屏幕坐标 2.坐标系转换 3.练习&#xff1a;判断鼠标单击的位置 步骤&#xff1a; 将脚本挂载到小…

32串口学习

基于之前的GPIO等工程&#xff0c;后面的上手难度就简单多了&#xff0c;主要是相关寄存器的设置。 void USART1_Config(void) {GPIO_InitTypeDef GPIO_InitStructure;USART_InitTypeDef USART_InitStructure;/* config USART1 clock */RCC_APB2PeriphClockCmd(RCC_APB2Periph…

在Ubuntu20.04(原为cuda12.0, gcc9.几版本和g++9.几版本)下先安装cuda9.0后再配置gcc-5环境

因为自己对Linux相关操作不是很熟悉&#xff0c;所以因为之前的代码报错之后决定要安cuda9.0&#xff0c;于是先安装了cuda9.0。里面用到的一些链接&#xff0c;链接文件夹时直接去copy它的路径&#xff0c;就不那么容易错了。 今天运行程序之后发现gcc环境不太匹配cuda9.0&am…

图书馆管理系统 1.架构项目以及加搭建项目

项目架构图 技术栈 后端 开发语言&#xff1a;java 开发环境&#xff1a;jdk11.0.12 开发工具&#xff1a;IntelliJ IDEA 2022.2.4 项目管理工具&#xff1a;maven 集成框架&#xff1a;springboot 权限控制框架&#xff1a;springSecurity 数据库&#xff1a;mysql 数据库框架…

Selenium不同版本配置自动下载驱动及打包细节

Selenium配置浏览器驱动 自动下载浏览器驱动的方法 selenium4.7.0自动下载浏览器驱动的方法 selenium4.11.0 或4.11.1手动设置浏览器驱动路径的方法pyinstaller打包程序时同时打包ChromeDriverchromedriver路径需要sys._MEIPASS的路径进行引用方法一&#xff1a;通过–add-data…

3、java虚拟机-类的生命周期-初始化阶段(与程序员有关)

一 、静态代码块执行顺序和字节码文件中的执行顺序以及什么赋值。 类的生命周期-初始化阶段-被static所修饰的常量才会被赋予值 初始化阶段-代码中静态代码块和静态变量的顺序和字节码中的执行顺序是一致的。 二、4种情况下&#xff0c;类会被初始化。 1、怎样查看类是…
最新文章