在 UUV Simulator 中创建新的模型描述包
文章目录
模型描述 (xxx_description) 中包含了用于 Gazebo 仿真的显示模型及运动学、动力学模型、推进器和舵模型、传感器等。
概述
以armsrov_description为例说明一下模型描述的结构,模型的文档结构如下图所示:
files
robots 文件夹中包含 default.xacro 宏脚本文件,该脚本文件将会创建armsrov水下机器人对象,同时会指定流体密度等uuv_plugin所需一些基本的参数。meshes 文件夹中包含一些用于显示和碰撞检测的三维模型网格文件。urdf 文件夹中包含多个 xacro 宏脚本文件,这些脚本文件描述了水下机器人的三维模型在 Gazebo 中的显示方式、水下机器人的重心浮心位置、质量矩阵、水动力参数等。launch 文件夹中的 xacro 宏脚本文件包含了水下机器人模型启动时的初始姿态和位置。package.xml 记录软件包信息。CMakeLists.txt 描述了软件包的编译构建信息。
在第一次创建模型描述的时候可以使用如下一行命令生成一个模型描述模板,然后基于这个模板进行添加和修改内容:
rosrun uuv_assistants create_new_robot_model --robot_name <ROBOT_NAME>导出显示模型
显示模型用于 Gazebo 仿真中显示被仿真的物体。Gazebo 支持 stl 和 dae 两种格式的 mesh 文件,stl 相对来说是一个比较常见的三维交换格式,大多数三维建模软件都可以直接导出和导入。dae 文件是 COLLADA 的模型文件,是一个基于XML的三维图形交换格式,大多数三维工程制图软件无法直接导出,例如 SolidWorks 就无法直接导出 dae 文件。dae 文件相对于 stl 文件的优点是可以携带颜色信息,可视化的效果较好。
为了导出 dae 文件需要借助一些三维动画制作软件。大概的流程是:
- 从 SolidWorks 中导出携带颜色信息的 wrl 格式的文件;
- 将携带颜色的 wrl 文件导入到 3D Max 中,在 3D Max 中确认好坐标轴的方向,导出为 dae 文件;
- 将 3D Max 中导出的 dae 文件导入到 Blender 中,在 Blender 中删除不必要的重复部分,确认好模型尺寸和轴的方向,再次导出 dae 文件;
从 SolidWorks 中导出 wrl 文件
导出前如果是装配体则需要先保存为零件。另存为时选择 VRML(*.wrl)。保存时最好先点击下方选项按钮,检查一下导出的版本是否是 1.0 ,单位是否是米。
wrl
wrl2
将 wrl 导入 3D Max,然后导出 dae 文件
首先将 wrl 模型导入 3D Max。
3dmax1
接着观察坐标轴的方向是否满足需求 (Gazebo 中 z 轴表示上下)。可以看到导入的模型坐标轴方向于 Gazebo 的要求不一致,需要对坐标轴做出修改满足 Gazebo 的要求。坐标轴的更改可以在 SolidWorks 中完成,也可以在 3D Max 中完成。
3dmax2
选中需要变换坐标轴的物体,右键后选择旋转,填入需要的旋转的值即可完成坐标轴转换。
导出时选择 AutoDesk Collada (*.DAE)。填写好导出文件名称后会弹出保存选项。在保存选项中需要确认单位是否是 米,轴转化中选择的轴的方向是否是 z 轴向上。
3dmax3
导入 Blender 并检查模型尺寸是否正确
通过 文件->导入 选项导入 dae 文件。
blender1
接着检查导入的模型的尺寸和轴的方向是否满足要求。然后可以根据需求,将水下机器人本体、舵板、推进器分别导出为 dae 文件。
配置显示模型
水下机器人本体的模型配置在 urdf/base.xacro 文件中:
<xacro:property name="visual_mesh_file" value="file://$(find auv_description)/meshes/body.dae"/>
<xacro:property name="collision_mesh_file" value="file://$(find auv_description)/meshes/body.stl"/>visual_mesh_file 表示在 Gazebo 中看到的模型,collision_mesh_file 表示 Gazebo 进行碰撞检测时用到的模型。为了减小 Gazebo 进行碰撞检测时的运算量可以使用简化的模型,而显示模型为了美观性则可以使用复杂的模型。
推进器和舵的模型配置在 urdf/actuators.xacro 文件中。
推进器的配置方式如下:
<xacro:thruster_macro robot_namespace="${namespace}" thruster_id="0">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:thruster_macro>每个推进器必须配置一个独有的 thruster_id。xyz 表示推进器的位置,rpy 表示推进器绕三个轴的角度(roll, pitch, yaw)。
推进器的模型文件在 urdf/snippets.xacro 文件中配置:
<xacro:property name="prop_mesh_file" value="file://$(find auv_description)/meshes/propeller.dae"/>舵的配置方式如下:
<xacro:fin_macro namespace="${namespace}" fin_id="0" mesh_filename="${fin_mesh_file}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:fin_macro>和推进器的配置一样 xyz 和 rpy 分别表示舵的位置和角度。
舵的模型文件同样在 urdf/snippets.xacro 文件中配置:
<xacro:property name="fin_mesh_file" value="file://$(find lauv_description)/meshes/fin.dae"/>todo…