gazebo添加livox传感器进行仿真

一、说明

因为课题原因,需要用到livox传感器,但是总拿着它去实验太费劲儿,所以想要在ros的gazebo环境里面进行仿真实验。在网上找了一圈,都没有详细的教程,所以自己摸索了一会儿,大致上解决了这个点。过程不难,在这里记录一下,一方面希望可以帮到其他有需要的人,另一方面也是给自己做个记录,防止忘了。

二、仿真环境

1、ubuntu20.04
2、ros是noetic
3、机器人小车用的是husky

三、配置过程

1、安装livox的SDK

下载链接:https://github.com/Livox-SDK/Livox-SDK
安装过程在代码包里面交代得比较清楚了,这里也贴一下。

git clone https://github.com/Livox-SDK/Livox-SDK.git
cd Livox-SDK
cd build && cmake ..
make
sudo make install

整个环境的兼容性比较高,编译没有出现什么错误。

2、安装livox的ROS驱动

下载链接:https://github.com/Livox-SDK/livox_ros_driver
安装步骤与一般的ros包无差别,下载后catkin_make即可。

git clone https://github.com/Livox-SDK/livox_ros_driver.git ws_livox/src
cd ws_livox
catkin_make

3、安装livox的仿真环境包

下载链接:https://github.com/Livox-SDK/livox_laser_simulation
注意:这个安装包,针对的是Ubuntu 18.04以及之前的版本,用Ubuntu 20.04编译的话,需要把它的CMakeLists.txt里面的编译器版本改为17,即:将下面这句话里的11改为17:

add_compile_options(-std=c++11)

否则会出现如下报错:

。。。error:anyis not a member of ‘std’。。。

详细可以参考,代码仓库的Issues#4

4、安装husky小车的仿真包

下载链接:https://github.com/husky/husky
安装过程不再赘述,期间可能会报一些依赖包缺失,缺啥安装啥就行。

5、把livox放到小车上(敲黑板!!!重点哈~

1、思考,两个独立的包,小车仿真可以开启,livox的仿真也可以开启,没道理说它俩放不到一起去。既然每个包,都是urdf文件,那么,是不是可以说,只要把这俩urdf文件的关键信息结合到一起,就能完成了呢?!试试看。
2、然后想起来,以前也给小车添加过VLP-16激光雷达,这俩或许可以相通。添加VLP-16的教程,大家可以参考以下两个链接:
教程一:ROS仿真笔记之——gazebo配置velodyne(引用CSDN博主:gwpscut)
教程二:[gazebo仿真]给模型添加多线激光雷达(引用CSDN博主:Travis.X)
3、有了上面的基础,就可以开整了,我们可以观察到,其实添加一个传感器,主要就是两部分:
**第一部分:**在你想要添加到的小车的URDF文件里,创建一个实体,用来代表这个传感器,并且将它固定到小车上,比如,我们现在想要把livox添加到husky的小车上,那么第一步,就是打开husky功能包里面的/husky/husky_description/urdf/husky.urdf.xacro这个文件,然后在那一堆link标签后面,添加:

<link name="laser_livox">
	<collision>
	  <origin xyz="0 0 0" rpy="0 0 0"/>  
	  <geometry>
		<box size="0.1 0.1 0.1"/>
	  </geometry>
	</collision>	
	<visual>
	  <origin xyz="0 0 0" rpy="0 0 0"/>
	  <geometry>
		<box size="0.1 0.1 0.1"/>
	  </geometry>
	</visual>
  </link>

这是创建了一个边长为0.1m的正方体,用来表示livox这个固态雷达,你也可以把它设置成你想要的形状,无关紧要,然后紧接着上面那段,添加一个关节,把它跟小车的坐标系连接起来:

<joint name="laser_livox_joint" type="fixed" >
    <origin xyz="0 0 0.5" rpy="0 0 0" />
    <parent link="base_link" />
    <child link="laser_livox"/>
</joint>

上面的完成之后,就可以进入到第二部分了。
第二部分:为上面的小方块注入灵魂,为它赋予固态雷达的使命:

<xacro:property name="horizontal_fov" value="70.4"/>
<xacro:property name="vertical_fov" value="70.4"/>
  <gazebo reference="laser_livox">
      <sensor type="ray" name="laser_livox">
        <pose>0 0 0 0 0 0</pose>
        <visualize>true</visualize>
        <update_rate>10</update_rate>
        <!-- This ray plgin is only for visualization. -->
        <plugin name="gazebo_ros_laser_controller" filename="liblivox_laser_simulation.so">
			<ray>
			  <scan>
				<horizontal>
				<samples>100</samples>
				<resolution>1</resolution>
				<min_angle>${
   -horizontal_fov/360*M_PI}</min_angle>
				<max_angle>${
   horizontal_fov/360*M_PI}</max_angle>
				</horizontal>
				<vertical>
				<samples>50</samples>
				<resolution>1</resolution>
				<min_angle>${
   -vertical_fov/360*M_PI}</min_angle>
				<max_angle>${
   vertical_fov/360*M_PI}</max_angle>
				</vertical>
			  </scan>
			  <range>
				<min>0.1</min>
				<max>200</max>
				<resolution>0.002</resolution>
			  </range>
			  <noise>
				<type>gaussian</type>
				<mean>0.0</mean>
				<stddev>0.01</stddev>
			  </noise>
			</ray>
          <visualize>true</visualize>
		  <samples>10000</samples>
		  <downsample>1</downsample>
		  <csv_file_name>package://livox_laser_simulation/scan_mode/mid70.csv</csv_file_name>
		  <ros_topic>/scan</ros_topic>
        </plugin>
      </sensor>
  </gazebo>

看到上面这一长串的标签型代码块,是不是内心来了个握草三连,这是啥?咋写的?为啥是这样?
别急,听我说,谢谢ni~不好意思,走错片场了。上面这一段其实就是livox_laser_simulation里的内容,具体文件是这里面的/livox_laser_simulation/urdf/livox_mid70.xacro。所以,只是把仿真包里面的核心代码复制过来了,至于这些参数,可以根据不同型号的雷达进行相应的调整。这里面把小方块和解释它身份的标签联系起来的是这句:

<gazebo reference="laser_livox">

到这里,这篇文章基本上就结束啦。最后贴上完整的小车urdf描述文件,供大家参考:

<?xml version="1.0"?>
<robot name="husky" xmlns:xacro="http://ros.org/wiki/xacro">
  <!-- IMU Link -->
  <xacro:arg name="imu_xyz"     default="$(optenv HUSKY_IMU_XYZ 0.19 0 0.149)"/>
  <xacro:arg name="imu_rpy"     default="$(optenv HUSKY_IMU_RPY 0 -1.5708 3.1416)"/>
  <xacro:arg name="imu_parent"  default="$(optenv HUSKY_IMU_PARENT base_link)"/>

  <!-- LMS1XX Laser Primary and Secondary -->
  <xacro:arg name="laser_enabled"           default="$(optenv HUSKY_LMS1XX_ENABLED 0)" />
  <xacro:arg name="laser_topic"             default="$(optenv HUSKY_LMS1XX_TOPIC front/scan)"/>
  <xacro:arg name="laser_prefix"            default="$(optenv HUSKY_LMS1XX_PREFIX front)"/>
  <xacro:arg name="laser_parent"            default="$(optenv HUSKY_LMS1XX_PARENT top_plate_link)"/>
  <xacro:arg name="laser_xyz"               default="$(optenv HUSKY_LMS1XX_XYZ 0.2206 0.0 0.00635)" />
  <xacro:arg name="laser_rpy"               default="$(optenv HUSKY_LMS1XX_RPY 0.0 0.0 0.0)" />

  <xacro:arg name="laser_secondary_enabled" default="$(optenv HUSKY_LMS1XX_SECONDARY_ENABLED 0)" />
  <xacro:arg name="laser_secondary_topic"   default="$(optenv HUSKY_LMS1XX_SECONDARY_TOPIC rear/scan)"/>
  <xacro:arg name="laser_secondary_prefix"  default="$(optenv HUSKY_LMS1XX_SECONDARY_PREFIX rear)"/>
  <xacro:arg name="laser_secondary_parent"  default="$(optenv HUSKY_LMS1XX_SECONDARY_PARENT top_plate_link)"/>
  <xacro:arg name="laser_secondary_xyz"     default="$(optenv HUSKY_LMS1XX_SECONDARY_XYZ -0.2206 0.0 0.00635)" />
  <xacro:arg name="laser_secondary_rpy"     default="$(optenv HUSKY_LMS1XX_SECONDARY_RPY 0.0 0.0 3.14159)" />

  <!-- UST10 Laser Primary  and Secondary -->
  <xacro:arg name="laser_ust10_front_enabled" default="$(optenv HUSKY_UST10_ENABLED 0)" />
  <xacro:arg name="laser_ust10_front_topic"   default="$(optenv HUSKY_UST10_TOPIC front/scan)" />
  <xacro:arg name="laser_ust10_front_prefix"  default="$(optenv HUSKY_UST10_PREFIX front)" />
  <xacro:arg name="laser_ust10_front_parent"  default="$(optenv HUSKY_UST10_PARENT top_plate_link)" />
  <xacro:arg name="laser_ust10_front_xyz"     default="$(optenv HUSKY_UST10_XYZ 0.2206 0.0 0.00635)" />
  <xacro:arg name="laser_ust10_front_rpy"     default="$(optenv HUSKY_UST10_RPY 0 0 0)" />

  <xacro:arg name="laser_ust10_rear_enabled"  default="$(optenv HUSKY_UST10_SECONDARY_ENABLED 0)" />
  <xacro:arg name="laser_ust10_rear_topic"    default="$(optenv HUSKY_UST10_SECONDARY_TOPIC rear/scan)" />
  <xacro:arg name="laser_ust10_rear_prefix"   default="$(optenv HUSKY_UST10_SECONDARY_PREFIX rear)" />
  <xacro:arg name="laser_ust10_rear_parent"   default="$(optenv HUSKY_UST10_SECONDARY_PARENT top_plate_link)" />
  <xacro:arg name="laser_ust10_rear_xyz
评论 31
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值