在gazebo里搭建一个livox mid360 + 惯导仿真平台测试 FAST-LIO2

在gazebo里搭建一个livox mid360 + 惯导仿真平台测试 FAST-LIO2

  • 前言
  • 立方体平台
  • 加入 livox mid360 激光雷达
  • 加入IMU模块
  • 调整底盘大小 并设计调用接口
  • 测试 Fast-Lio2

前言

livox mid360 在官网一直没有货,在gazebo里可以仿真该雷达形式的点云。

但是其只发布雷达的数据,没有imu数据,实际的雷达是可以发布既有雷达也有imu的数据的

运行 FAST-LIO2 也需要雷达和惯导的数据

本篇博客在gazebo中搭建了一个有livox mid360 和惯导的平台,并成功运行了FAST-LIO2

立方体平台

先做一个最简单的立方体平台,用来放livox mid360 和惯导

编写一个xacro文件,如下

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="example"><!-- Base Footprint --><link name="base_footprint" /><!-- Base Link --><joint name="footprint" type="fixed" ><parent link="base_footprint" /><child link="link_platform" /><origin xyz="0 0 0.05" rpy="0 0 0" /></joint><link name="link_platform" ><visual><geometry><box size="0.5 0.5 0.1" /></geometry></visual><collision><geometry><box size="0.5 0.5 0.1" /></geometry></collision><inertial><origin xyz="0 0 0"/><mass value="0.01"/><inertia ixx="0.001" ixy="0.0" ixz="0.0"iyy="0.001" iyz="0.0" izz="0.001" /></inertial></link></robot>

写一个launch文件来启动它,加载到gazebo和rivz中

<?xml version="1.0" ?>
<launch><arg name="paused" default="false"/><arg name="use_sim_time" default="true"/><arg name="gui" default="true"/><arg name="headless" default="false"/><arg name="debug" default="false"/><arg name="verbose" default="false"/><!-- Start gazebo and load the world --><include file="$(find gazebo_ros)/launch/empty_world.launch" ><arg name="paused" value="$(arg paused)"/><arg name="use_sim_time" value="$(arg use_sim_time)"/><arg name="gui" value="$(arg gui)"/><arg name="headless" value="$(arg headless)"/><arg name="debug" value="$(arg debug)"/><arg name="verbose" value="$(arg verbose)"/></include>
![在这里插入图片描述](https://img-blog.csdnimg.cn/1a7fdea939be47c8b0a1c6d7d064e1fa.png)![在这里插入图片描述](https://img-blog.csdnimg.cn/1a7fdea939be47c8b0a1c6d7d064e1fa.png)<!-- Spawn the platform --><param name="robot_description" command="$(find xacro)/xacro --inorder '$(find livox_laser_simulation)/urdf/mid360_IMU_platform.xacro' " /><node pkg="gazebo_ros" type="spawn_model" name="spawn_model" args="-urdf -param /robot_description -model example"/><node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"><param name="publish_frequency" type="double" value="30.0" /></node><!-- RViz --><arg name="rviz" default="true"/><node if="$(arg rviz)" pkg="rviz" type="rviz" name="$(anon rviz)" respawn="false" output="screen" args="-d $(find livox_laser_simulation)/rviz/mid360_IMU_platform.rviz" /></launch>

启动

roslaunch livox_laser_simulation mid360_IMU_platform.launch

gazebo 和rviz 中会出现下面的立方体,具体的尺寸和颜色可以最后再根据雷达和惯导再调整
在这里插入图片描述

加入 livox mid360 激光雷达

下一步向平台上加入 livox mid360 激光雷达, 放在平台的中心。

向 livox_laser_simulation/urdf/mid360_IMU_platform.xacro 文件中加入下面代码

  <joint name="lidar_platform" type="fixed" ><parent link="link_platform" /><child link="livox_base" /><origin xyz="0 0 0.08" rpy="0 0 0" /></joint><xacro:include filename="$(find livox_laser_simulation)/urdf/livox_mid360.xacro"/><xacro:Livox_Mid360 name="livox"/>

再次启动launch文件即可,看到平台中央多了livox mid360 雷达
在这里插入图片描述
确认雷达输出点云正常,可向周围加入几个物体测试

在这里插入图片描述
点云正常

加入IMU模块

向平台中加入IMU模块,放在雷达的前方一点

向 livox_laser_simulation/urdf/mid360_IMU_platform.xacro 文件中加入下面代码

    <!--imu --><link name="imu_base_link"><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry ><box size="0.03 0.03 0.03" /></geometry></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry ><box size="0.03 0.03 0.03" /></geometry></collision>   <inertial><mass value="0.001"/><inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/></inertial> </link><gazebo reference="imu_base_link"><material>Gazebo/Green</material><turnGravityOff>true</turnGravityOff></gazebo><joint name="imu_platform_joint" type="fixed"><parent link="link_platform"/><child link="imu_base_link"/><origin xyz="0.05 0 0.065" rpy="0 0 0" /><axis xyz="0 0 1" /></joint><gazebo reference="imu_base_link"><gravity>true</gravity><sensor name="imu_sensor" type="imu"><always_on>true</always_on><update_rate>200</update_rate><visualize>true</visualize><topic>/livox/imu</topic><plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin"><topicName>/livox/imu</topicName>         <bodyName>imu_base_link</bodyName><updateRateHZ>200.0</updateRateHZ>    <gaussianNoise>0.00329</gaussianNoise>   <xyzOffset>0 0 0</xyzOffset>     <rpyOffset>0 0 0</rpyOffset><frameName>imu_base_link</frameName>        </plugin><pose>0 0 0 0 0 0</pose></sensor></gazebo>

再次启动launch文件即可,看到平台中 的livox mid360 雷达 前多了一个绿色的小方块,它即为刚建立惯导模型
在这里插入图片描述
通过rostopic 查看 惯导数据是否正常
在这里插入图片描述
数据正常

调整底盘大小 并设计调用接口

下一步需要调整底盘平台的大小,能够放下雷达和惯导即可

将底盘尺寸改为如下

<box size="0.15 0.1 0.1" />

在这里插入图片描述
回来平台的前方挂个双目也不错

带有雷达和惯导的平台搭建完了

但是这个平台无法运动,也就完成不了建图,如果运行需要将平台挂载到小车或者无人机上。
所以需要对这个平台设计好接口,方便其它移动平台挂载。

修改 livox_laser_simulation/urdf/mid360_IMU_platform.xacro 这个文件

最后的文件如下:

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="example"><!-- Base Footprint --><!-- <link name="base_footprint" /> --><xacro:macro name="LivoxMid360_IMU_Plantform" params="name:=mid360_imu_plantform parent_link_name:=base_link x:=0.0 y:=0.0 z:=0.05 r:=0.0 p:=0.0 yaw:=0.0"><joint name="${name}_joint" type="fixed" ><parent link="${parent_link_name}" /><child link="link_platform" /><origin xyz="${x} ${y} ${z}" rpy="${r} ${p} ${yaw}" /></joint><!-- link_platform --><link name="link_platform" ><visual><geometry><box size="0.15 0.1 0.1" /></geometry></visual><collision><geometry><box size="0.15 0.1 0.1" /></geometry></collision><inertial><origin xyz="0 0 0"/><mass value="0.001"/><inertia ixx="0.001" ixy="0.0" ixz="0.0"iyy="0.001" iyz="0.0" izz="0.001" /></inertial></link><gazebo reference="link_platform"><turnGravityOff>false</turnGravityOff></gazebo><joint name="lidar_platform_joint" type="fixed" ><parent link="link_platform" /><child link="livox_base" /><origin xyz="0 0 0.08" rpy="0 0 0" /></joint><!--lidar --><xacro:include filename="$(find livox_laser_simulation)/urdf/livox_mid360.xacro"/><xacro:Livox_Mid360 name="livox"/><!--imu --><link name="imu_base_link"><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry ><box size="0.03 0.03 0.03" /></geometry></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry ><box size="0.03 0.03 0.03" /></geometry></collision>  <inertial><mass value="0.001"/><inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/></inertial></link><gazebo reference="imu_base_link"><material>Gazebo/Green</material><turnGravityOff>false</turnGravityOff></gazebo><joint name="imu_platform_joint" type="fixed"><parent link="link_platform"/><child link="imu_base_link"/><origin xyz="0.05 0 0.065" rpy="0 0 0" /><axis xyz="0 0 1" /></joint><gazebo reference="imu_base_link"><gravity>true</gravity><sensor name="imu_sensor" type="imu"><always_on>true</always_on><update_rate>200</update_rate><visualize>true</visualize><topic>/livox/imu</topic><plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin"><topicName>/livox/imu</topicName>         <bodyName>imu_base_link</bodyName><updateRateHZ>200.0</updateRateHZ>    <gaussianNoise>0.00329</gaussianNoise>   <xyzOffset>0 0 0</xyzOffset>     <rpyOffset>0 0 0</rpyOffset><frameName>imu_base_link</frameName>        </plugin><pose>0 0 0 0 0 0</pose></sensor></gazebo></xacro:macro></robot>

将其挂载到飞机上,代码如下:的几款雷达进行了仿真测试。

  <xacro:include filename="$(find livox_laser_simulation)/urdf/mid360_IMU_platform.xacro"/><xacro:LivoxMid360_IMU_Plantform name ="mid360_imu_plantform" parent_link_name="${namespace}/base_link" x="0"  y="0" z="0.08" r="0"  p="0" yaw="0" /> 

最终效果如下:
在这里插入图片描述

测试 Fast-Lio2

用这个平台跑Fast-Lio2 还需要有一步,就是修改雷达的仿真程序,使其发送Livox的Custcom格式的点云,这个方法会放到其它博客中

调通后,用其跑Fast-Lio2 效果如下:

在这里插入图片描述

在这里插入图片描述

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

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

Spire.Office 8.11.2 for NET fix Crack

内容摘自来自互联网------或者SDK官方本身手册 Spire.Doc for .NET A professional Word .NET library designed to create, read, write, convert and print Word document files in any .NET ( C#, VB.NET, ASP.NET, .NET Core, Xamarin ) application with fast and high qu…

Aurora8B10B(一) 从IP配置界面学习Aurora

一. 简介 哈喽&#xff0c;大家好&#xff0c;好久没有给大家写FPGA技术的文章&#xff0c;是不是已经忘记我是做FPGA的啦&#xff0c;O(∩_∩)O哈哈~。 这里将会给大家分享我学习到的第一个高速接口Aurora8B10B&#xff0c;有点复杂&#xff0c;但不是特别复杂&#xff0c;对…

使用vscode的remotessh插件远程连接的时候被要求重复输入密码

问题描述&#xff1a; 需要远程连接服务器&#xff0c;使用ssh&#xff0c;我用到的是vscode里面的remotessh插件。配置好config以后 HostHostNameUserPortIdentifyFile进入到了vscode的密码登录界面&#xff0c;但是一直被要求循环输入密码&#xff0c;很奇怪&#xff0c;去…

论文阅读——DINOv

首先是关于给了提示然后做分割的一些方法的总结&#xff1a; 左边一列是prompt类型&#xff0c;右边一列是使用各个类型的prompt的模型。这些模型有分为两大类&#xff1a;Generic和Refer&#xff0c;通用分割和参考分割。Generic seg 是分割和提示语义概念一样的所有的物体&am…

LLM之Agent(二):BabyAGI的详细教程

BabyAGI是一个 AI 支持的任务管理系统&#xff08;Python脚本&#xff09;&#xff0c;使用 OpenAI 和 Pinecone API 创建, 优先级排序和执行任务。该系统背后的主要思想是基于先前任务的结果和预定义的目标创建任务。脚本然后使用 OpenAI 的自然语言处理&#xff08;NLP&#…

leetCode 93.复原 IP 地址 + 回溯算法 + 图解 + 笔记

93. 复原 IP 地址 - 力扣&#xff08;LeetCode&#xff09; 有效 IP 地址 正好由四个整数&#xff08;每个整数位于 0 到 255 之间组成&#xff0c;且不能含有前导 0&#xff09;&#xff0c;整数之间用 . 分隔。 例如&#xff1a;"0.1.2.201" 和 "192.168.1.1…

CS 2520nonono

CS 2520nonono WeChat&#xff1a;yj4399_​​​​​ Sina Visitor System High-level●3 Congestion Control Algorithms:○TCP Reno:■additive increase, multiplicative decrease function to adjust window size for every RTTuntil a packet loss is detected○TCP CUBI…

用java实现拼图小游戏

1、了解拼图游戏基本功能&#xff1a; 拼图游戏内容由若干小图像块组成的&#xff0c;通过鼠标点击图像块上下左右移动&#xff0c;完成图像的拼凑。 2、拼图游戏交互界面设计与开发&#xff1a; 通过创建窗体类、菜单、中间面板和左右面板完成设计拼图的交互界面 &#xff…

分享从零开始学习网络设备配置--任务4.3 使用动态路由RIPng实现网络连通

任务描述 某公司使用IPv6技术搭建企业网络&#xff0c;由于静态路由需要管理员手工配置&#xff0c;在网络拓扑发生变化时&#xff0c;也不会自动生成新的路由&#xff0c;因此采用IPv6动态路由协议RIPng实现网络连通&#xff0c;实现任意两个节点之间的通信&#xff0c;并降低…

基于SpringBoot学生读书笔记共享

摘 要 本论文主要论述了如何使用JAVA语言开发一个读书笔记共享平台 &#xff0c;本系统将严格按照软件开发流程进行各个阶段的工作&#xff0c;采用B/S架构&#xff0c;面向对象编程思想进行项目开发。在引言中&#xff0c;作者将论述读书笔记共享平台的当前背景以及系统开发的…

第16关 革新云计算:如何利用弹性容器与托管K8S实现极速服务POD扩缩容

------> 课程视频同步分享在今日头条和B站 天下武功&#xff0c;唯快不破&#xff01; 大家好&#xff0c;我是博哥爱运维。这节课给大家讲下云平台的弹性容器实例怎么结合其托管K8S&#xff0c;使用混合服务架构&#xff0c;带来极致扩缩容快感。 下面是全球主流云平台弹…

对抗产品团队中的认知偏误:给产品经理的专家建议

今天的产品经理面临着独特的挑战。他们不仅需要设计和构建创新功能&#xff0c;还必须了解这些功能将如何为客户带来价值并推进关键业务目标。如果不加以控制&#xff0c;认知偏差可能会导致您构建的内容与客户想要的内容或业务需求之间不一致。本文将详细阐述产品经理可以避免…

下载MySQL JDBC驱动的方法

说明 java代码通过JDBC访问MySQL数据库&#xff0c;需要MySQL JDBC驱动。 例如&#xff0c;下面这段代码&#xff0c;因为找不到JDBC驱动&#xff0c;所以执行会报异常&#xff1a; package com.thb;public class JDBCDemo {public static void main(String[] args) throws …

网络基础_1

目录 网络基础 协议 协议分层 OSI七层模型 网络传输的基本流程 数据包的封装和分用 IP地址和MAC地址 网络基础 网络就是不同的计算机之间可以进行通信&#xff0c;前面我们学了同一台计算机之间通信&#xff0c;其中有进程间通信&#xff0c;前面学过的有管道&#xff…

Redis之秒杀系统

目录 Redis 秒杀 Mysql数据库设计 Mysql秒杀实现 MysqlRedis秒杀实现 秒杀是一种高并发场景&#xff0c;通常指的是在短时间内&#xff08;秒级别&#xff09;有大量用户同时访问某个商品或服务&#xff0c;争相抢购的情景。在这种情况下&#xff0c;系统需要处理大量并发请…

Openai通用特定领域的智能语音小助手

无穷尽的Q&A 钉钉...钉钉... 双双同学刚到工位,报销答疑群的消息就万马纷沓而来。她只能咧嘴无奈的摇摇头。水都还没有喝一口就开始“人工智能”的去回复。原本很阳光心情开始蒙上一层薄薄阴影。在这无休无止的Q&A中&#xff0c;就算你对工作有磐石一般强硬&#xff0…

Linux C/C++高级全栈开发(后端/游戏/嵌入式/高性能网络/存储/基础架构)

Linux C/C高级全栈开发是一个涉及到多个领域的综合性技术要求&#xff0c;需要对Linux系统、C/C编程语言以及各种相关的技术进行深入的理解和应用。 下面是一些涵盖的主要技术领域和技能要点&#xff1a; Linux系统基础&#xff1a;熟悉Linux操作系统的原理和常用命令&#xf…

Linux下的文件IO之系统IO

1. 知识点 读入写出&#xff0c;切记以我们程序为中心向文件或者别的什么东西读入写出&#xff08;输入流输出流&#xff09; 人话就是 文件向我们程序就是读入 程序向文件或者别的什么就是写出 2. open打开文件 open.c /****************************************************…

手写VUE后台管理系统5 - 整合状态管理组件pinia

整合状态管理组件 安装整合创建实例挂载使用 pinia 是一个拥有组合式 API 的 Vue 状态管理库。 pinia 官方文档&#xff1a;https://pinia.vuejs.org/zh/introduction.html 安装 yarn add pinia整合 所有与状态相关的文件都放置于项目 src/store 目录下&#xff0c;方便管理 在…

2021年6月3日 Go生态洞察:Fuzzing技术的Beta测试

&#x1f337;&#x1f341; 博主猫头虎&#xff08;&#x1f405;&#x1f43e;&#xff09;带您 Go to New World✨&#x1f341; &#x1f984; 博客首页——&#x1f405;&#x1f43e;猫头虎的博客&#x1f390; &#x1f433; 《面试题大全专栏》 &#x1f995; 文章图文…