欢迎来到中级模块!本模块将指导您完成创建新模拟功能并将该功能贡献给 Gazebo 的过程。
我们基础知识需要: Gazebo 、Linux。我们还假设您是一位专业的教程阅读者(仔细、完整地阅读所有内容)。
在本系列教程中,我们将创建一个 Velodyne HDL-32 LiDAR,我们将逐步完成
上述每个主题都将有专门的教程解说。本教程的 重点是 Velodyne SDF 模型的创建。
创建新模型的第一步是收集有关模型的信息。在这种情况下,Velodyne 激光雷达公司在其网站 Velodyne 的 HDL-32E 环绕激光雷达传感器 | 上提供了有关其传感器的文档。 Velodyne 激光雷达。如果没有关于模型的详细信息,那么您可以测量物理版本,询问制造商的规格,或者在最坏的情况下猜测。
根据 Velodyne 文档,我们将创建一个传感器,该传感器具有:
生成新文件.
- cd
- gedit velodyne.world
使用地平面和灯光填充世界文件:
- <sdf version="1.5">
- <world name="default">
-
-
- <include>
- <uri>model://sunuri>
- include>
-
-
- <include>
- <uri>model://ground_planeuri>
- include>
- world>
- sdf>
接下来,我们将 Velodyne LiDAR 的基础知识添加到 SDF 世界文件中。我们将使用 Velodyne 传感器尺寸来构建一个基圆柱体和一个顶部圆柱体。下面是 Velodyne 2D 绘图的屏幕截图。
将以下内容复制到 SDF 世界文件中,直接位于 标记之前。
- <model name="velodyne_hdl-32">
-
- <link name="base">
-
-
- <pose>0 0 0.029335 0 0 0pose>
- <collision name="base_collision">
- <geometry>
- <cylinder>
-
- <radius>.04267radius>
- <length>.05867length>
- cylinder>
- geometry>
- collision>
-
-
- <visual name="base_visual">
- <geometry>
- <cylinder>
- <radius>.04267radius>
- <length>.05867length>
- cylinder>
- geometry>
- visual>
- link>
-
-
- <link name="top">
-
-
- <pose>0 0 0.095455 0 0 0pose>
- <collision name="top_collision">
- <geometry>
- <cylinder>
-
- <radius>0.04267radius>
- <length>0.07357length>
- cylinder>
- geometry>
- collision>
-
-
- <visual name="top_visual">
- <geometry>
- <cylinder>
- <radius>0.04267radius>
- <length>0.07357length>
- cylinder>
- geometry>
- visual>
- link>
- model>
在构建新模型时,定期尝试小的更改是个好主意。启动 Gazebo 已暂停,以便您可以在物理引擎不改变模型姿势的情况下查看模型。还有一些其他图形工具可以帮助开发过程,我们将在本教程的过程中介绍这些工具。
暂停运行 Velodyne 世界(-u 参数)。
- cd
- gazebo velodyne.world -u
默认情况下,您会在模型中看到
此时,我们的 Velodyne 模型缺少惯性矩等动态属性。物理引擎使用惯性信息来计算模型在受力时的行为方式。具有不正确或没有惯性值的模型将以奇怪的方式表现。
1)首先可视化当前的惯性值。在 Gazebo 运行时,右键单击 Velodyne 并选择 View->Inertia。这将导致出现两个紫色框。
通常,每个紫色框应与与其关联的链接的大小大致匹配。您会注意到当前的惯性框非常大,这是由于我们的模型缺少惯性信息。
我们可以通过指定质量和惯性矩阵来为链接添加惯性。我们将质量基于 Velodyne 的指定质量,即 1.3 千克,并给予基本链接多数(此分布是我们的猜测)。惯性矩矩阵可以使用维基百科上的方程计算。
以下是基础链接的惯性值。将
块复制到指定位置。
- <model name="velodyne_hdl-32">
- <link name="base">
- <pose>0 0 0.029335 0 0 0pose>
- <inertial>
- <mass>1.2mass>
- <inertia>
- <ixx>0.001087473ixx>
- <iyy>0.001087473iyy>
- <izz>0.001092437izz>
- <ixy>0ixy>
- <ixz>0ixz>
- <iyz>0iyz>
- inertia>
- inertial>
接下来为顶部链接添加惯性值。将以下 <惯性> 块复制到指定位置。
- <link name="top">
- <pose>0 0 0.095455 0 0 0pose>
- <inertial>
- <mass>0.1mass>
- <inertia>
- <ixx>0.000090623ixx>
- <iyy>0.000090623iyy>
- <izz>0.000091036izz>
- <ixy>0ixy>
- <ixz>0ixz>
- <iyz>0iyz>
- inertia>
- inertial>
有了惯性值,可视化应该类似于下图。
在模型创建过程的这一点上,您应该拥有一个具有正确视觉、碰撞和惯性属性的模型。我们现在将移动到关节。
关节定义链接之间的约束。在机器人领域,最常见的关节类型是旋转的。旋转关节定义了两个连杆之间的单个旋转自由度。可以在 SDF 网站上找到完整的关节列表。
当然,可以可视化关节。运行 Gazebo 时,右键单击模型,然后选择查看 -> 关节。关节通常位于模型内,因此您可能必须使模型透明才能看到关节可视化(右键单击模型并选择查看->透明)。
我们首先必须在 Velodyne 模型中添加一个关节。关节将是旋转的,因为顶部连杆将相对于基本连杆旋转。
打开 SDF 世界,并在 标签前添加一个旋转关节。
- <joint type="revolute" name="joint">
-
-
- <pose>0 0 -0.036785 0 0 0pose>
-
-
- <parent>baseparent>
-
-
- <child>topchild>
-
-
- <axis>
-
-
- <xyz>0 0 1xyz>
-
-
- <limit>
-
-
- <lower>-10000000000000000lower>
- <upper>10000000000000000upper>
- limit>
- axis>
- joint>
运行 SDF 世界,暂停并可视化关节。
gazebo velodyne.world -u
View->Joints
View->Transparent
我们还可以使用 Joint Command 图形工具验证关节是否正确旋转。拖动主窗口上打开的右侧面板,然后选择 Velodyne 模型。
使用此小部件中的“力”选项卡向关节施加较小的力,0.001 即可。取消暂停世界,您应该会看到可视化关节开始围绕模型的 Z 轴旋转。
至此,我们有了一个具有有效惯性、碰撞和关节属性的 Velodyne 模型。在下一节中,我们将介绍模型的最后一部分,即传感器的添加。
传感器用于从环境或模型生成数据。在本节中,我们将为 Velodyne 模型添加一个光线传感器。 Gazebo 中的射线传感器由一个或多个光束组成,这些光束会产生距离和潜在的强度数据。
一个射线传感器由一个
Velodyne 传感器需要垂直射线,然后旋转。我们将其模拟为旋转的水平风扇。我们采用这种方法是因为在 Gazebo 中可视化数据会更容易一些。 Velodyne 规范表明 HDL-32 有 32 条射线,垂直视场介于 +10.67 和 -30.67 度之间。
我们将光线传感器添加到顶部链接。将以下内容复制到
<link name="top"> 元素,在velodyne.world文件内
- <sensor type="ray" name="sensor">
-
-
- <pose>0 0 -0.004645 1.5707 0 0pose>
-
-
- <visualize>truevisualize>
-
-
- <update_rate>30update_rate>
- sensor>
接下来,我们将添加
- <ray>
-
-
- <scan>
-
-
- <horizontal>
-
- <samples>32samples>
-
-
- <resolution>1resolution>
-
-
- <min_angle>-0.53529248min_angle>
-
-
- <max_angle>0.18622663max_angle>
- horizontal>
- scan>
-
-
- <range>
-
-
- <min>0.05min>
-
-
- <max>70max>
-
-
- <resolution>0.02resolution>
- range>
- ray>
再次启动模拟,您应该可以看到 32 个传感器光束在没有暂停时。
现在我们有了 Velodyne LiDAR 模型,我们可以通过三种方式对其进行改进:
第一个改进将在其它教程中解决。