简介
需求:在Gazebo中实现激光测距
描述:在urdf没有找到专用激光测距传感器(只有相机carmera,激光雷达ray),这里我们将激光雷达ray配置成单线单采样的激光测距传感器。
实现流程:
- 创建urdf激光测距传感器link物理模型;
- gazebo物理引擎配置及驱动实现。
urdf模型(link/joint)
照自己需求实现物理模型样式即可,这里我们直接用一个Box表示。
<!--激光测距传感器物理参数:长宽高质量等-->
<xacro:property name="raydis_length" value="0.02"/>
<xacro:property name="raydis_width" value="0.025"/>
<xacro:property name="raydis_height" value="0.044"/>
<xacro:property name="raydis_mass" value="0.05"/>
<!--Box惯性矩阵xacro宏-->
<xacro:macro name="Box_interial_matrix" params="m l w h">
<inertial>
<mass value="${m}"/>
<inertia ixx="${m*(h*h+l*l)/12}" ixy="0.0" ixz="0.0" iyy="${m*(w*w+l*l)/12}" iyz="0.0" izz="${m*(w*w+h*h)/12}"/>
</inertial>
</xacro:macro>
<!--世界坐标系-->
<link name="world"/>
<!--激光距离传感器物理模型-->
<link name="raydis">
<visual>
<geometry>
<box size="${raydis_length} ${raydis_width} ${raydis_height}"/>
</geometry>
<origin xyz="0 0 0" rpy="0.0 0.0 0.0"/>
<material name="green">
<color rgba="0.0 1.0 0.0 0.5"/>
</material>
</visual>
<collision>
<geometry>
<box size="${raydis_length} ${raydis_width} ${raydis_height}"/>
</geometry>
<origin xyz="0 0 0" rpy="0.0 0.0 0.0"/>
</collision>
<xacro:Box_interial_matrix m="${raydis_mass}" l="${raydis_length}" w="${raydis_width}" h="${raydis_height}"/>
</link>
<!--传感器与世界坐标系位姿关系-->
<joint name="raydis_world" type="fixed">
<parent link="world"/>
<child link="raydis"/>
<origin xyz="0.5 0.5 0.0671" rpy="0.0 0.0 0.0"/>
</joint>
gazebo物理引擎配置及驱动
要在Gazebo中实现仿真还需要配置物理引擎及驱动
<gazebo reference="raydis">
<material>Gazebo/Yellow</material>
<sensor name="raydisSensor" type="ray">
<pose>0 0 0 0 1.570796 0</pose>
<!--在Gazebo中现实激光-->
<visualize>true</visualize>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.0221</min>
<max>0.20</max>
<resolution>0.0001</resolution>
</range>
</ray>
<plugin name="gazebo_raydis" filename="libgazebo_ros_laser.so">
<topicName>/raydis</topicName>
<frameName>raydis</frameName>
</plugin>
</sensor>
</gazebo>
代码说明:
<pose>0 0 0 0 1.570796 0</pose>
:激光位姿相对传感器物理模型绕x轴翻转90度(即让水平面变成垂直面,当然也可以修改传感器物理模型相对world坐标的位姿)。- scan扫描参数配置:
<samples>1</samples>
激光线数;<resolution>1</resolution>
每线扫描点数;min_angle/max_angle扫描角度 - range测距范围:min不能小于传感器物理模型尺寸(中心到外壳距离),否则传感器输出值恒为中心到外壳距离。