自己制作URDF
碰撞模型和v-hacd简化
URDF需要两种obj模型,分别是visual中的纹理模型和collision中的碰撞模型。通常来说可以直接将精细的纹理模型作为碰撞模型,但是这样仿真速度和仿真效果都不太理想。通过v-hacd算法可以完成纹理模型的简化:
- 通过Pybullet中的vhacd进行转化,但是兼容性比较差,有些obj不兼容会报错。
- 通过Blender软件 + vhacd插件转化,兼容性高,但是Blender软件本身稳定性有点差,经常闪退,需要检查一下导出的obj文件是否正常。https://github.com/andyp123/blender_vhacd 。
具体代码放在https://github.com/JosepLeder/CLKRobovat/blob/main/tools/obj2urdf.py 。
单obj对象物体
大部分物体采用单个obj的组成形式,即一个obj文件只包含了一个obj对象。
其中在visual_meshes中的obj是比较精细复杂的,如下图,每一个点代表obj中的一个坐标。
而在collision_meshes中的obj则做了简化
多obj对象物体
一部分的物体采用多个obj对象共同组成一个碰撞模型的组织形式,但纹理模型仍旧由单个obj对象构成。
如下图所示,碰撞模型经过了简化,并且由瓶盖,瓶颈,瓶身,三个obj对象组成。
关于抓手伸不到碗底的问题
如1.2所示,这种由多个obj对象构成的碰撞模型,其方向和纹理模型不同,所以会导致看上去抓手伸向的是碗底,其实是碗壁。需要确保纹理模型和碰撞模型的方向和坐标系是相同的,将纹理模型沿x轴旋转90°后可以正确模拟。
结论
在物体集中collision_meshes中的obj文件是已经经过v-hacd简化了的,所以可以拿来直接用。在urdf中的visual采用visual.obj,在collision中采用collision.obj。
inertia部分
com
之前重心过大是因为直接采用了meshes中的texutured.obj文件计算产生重心,但是在Blender软件中同时查看collision.obj和textured.obj时发现,后者的大小是前者的千倍,所以自然重心要大很多。现在采用visual_meshes中的obj(大小和collision.obj相同),重心的数值大小比较正常。
同时,之前用的obj2urdf模块将重心放在visual和collision中的origin属性显示,这样是错误的。这里的xyz表示的只是碰撞模型和纹理模型相对于父节点偏移的位置,而inertia中的xyz还是[0, 0, 0],也就是重心还是在物体的坐标原点,仿真会出现错误。具体可以看这个文档http://wiki.ros.org/urdf/XML/link 。
所以正确的方式应该是collision和visual中的origin的xyz属性都设为0,在inertia中的origin的xyz属性中设置重心。
moi
之前moi设置错误。在不确定的时候应当设置为ixx, iyy, izz = 1e-3,在查看trimesh文档的时候发现,调用trimesh.moment_inertia方法可以直接计算返回物体的惯性矩阵。
1 | import trimesh |
结果
最终的urdf文件如下:
1 | <robot name="bear_stationery_box"> |