MuJoCo 是目前机器人强化学习中比较流行的仿真器,本文主要记录自己将实验室的机器人 urdf 模型转换为 mujoco 能够加载的 xml 格式的过程。
官方论坛 和 官方文档 提供了一些常见的机器人模型,在修改 xml 的过程中可以参考。
本文主要参考资料为官方文档和 文章后附的参考。
MuJoCo的模型有三种:xx.mjb (二进制文件), xx.txt, xx.xml, 其中比较常用的是xml格式的,便于阅读和修改。
<link name="dummy">
</link>
<joint name="dummy_joint" type="fixed">
<parent link="dummy"/>
<child link="base_link"/>
</joint>
不加在rviz中运行的时候可能会报错(经测试可以不加)。
<mujoco>
<compiler
meshdir="/home/lee/catkin_ws/src/sys/meshes/"
balanceinertia="true"
discardvisual="false" />
</mujoco>
不加会丢失模型视觉效果(只存在碰撞体信息)。
cd /home/(your name)/.mujoco/mujoco200/bin
./compile /path/to/model.urdf /path/to/model.xml
在转换的过程中如果零件非常复杂是没办法转换的,所以要尽量保证自己的模型尽量简化。
./simulate /path/to/model/xml
如果mujoco以及在打开的状态下,可以将模型拖进窗口查看效果
如果是比较复杂的模型,建议先进行简化处理。
URDF 的 mesh 文件通常有两类:包含材质颜色等信息的 dae 文件(非必须)与用于碰撞的 stl 文件。由于 MuJoCo 并不支持 dae 文件,只支持stl文件,因此,如果 URDF 模型中有 dae 文件,需要全部转换为stl文件。可以使用 MeshLab ,或在线网站1 2 等进行转换。
一般 ROS 系统加载 URDF 模型,很多都会分开成很多子部分加载,但是 MuJoCo 是不能识别 ROS 的 package 路径的,所以最好把所有的 mesh 文件单独拷贝到一个文件夹内,同时保持唯一的命名。
ROS 系统很多采用 xacro 格式,此处需要转换成一个单一的 urdf 文件格式,同时 mesh 文件改为绝对路径,保证可以找到相应的 mesh 文件。也要注意把对应的 dae 文件格式修改为stl文件格式。最后,在 xacro/urdf 文件添加一些必要的 MuJoCo 的 tag 用于控制编译选项。
<mujoco>
<compiler
meshdir="../meshes_mujoco/"
balanceinertia="true"
discardvisual="false" />
</mujoco>
其他tag可以参考链接。 meshdir 是必须的,如果编译时有以下 bug ,则需要添加 balanceinertia
Error: inertia must satisfy A + B >= C; use 'balanceinertia' to fix
Object name = inertial_link, id = 3
discardvisual 这个 tag 默认是true,也就是丢掉视觉效果部分,保留碰撞部分。如果模型很复杂,它会把很多 mesh 文件进行简化,变成球、圆柱、立方体等,视觉效果会差很多,因此建议设为false,具体参考。另外,在MuJoCo的界面,可以通过按键盘数字键 0 和 1 进行视觉上的切换(视觉mesh与碰撞mesh)。
从xacro文件生成urdf文件的命令(如果有urdf文件则不需要此步):
rosrun xacro xacro --inorder model.xacro > model.urdf
检查urdf文件:
check_urdf model.urdf
在RViz中可视化:
roslaunch urdf_tutorial display.launch model:=path/to/your/urdf/file
在确认 URDF 模型没有问题后,进入 MuJoCo 的可执行文件夹内执行命令进行转换(如默认的 ~/mujoco/mujoco200/bin ):
./compile /path/to/model.urdf /path/to/model.mjb
./compile /path/to/model.urdf /path/to/model.txt
./compile /path/to/model.urdf /path/to/model.xml
官方说明可以转换成三种模型,我们一般用xml的格式。
./compile
Usage: compile infile outfile
infile can be in mjcf, urdf, mjb format
outfile can be in mjcf, mjb, txt format
测试生成的基本模型:
$ ./simulate /path/to/model.xml
由于上面生成的模型只是最基本的模型,仅包含基本的运动学链,缺少物理属性,如此处所说,还需要添加一些其他的 tag ,具体根据需要可以查看官方文档。
https://blog.csdn.net/feisy/article/details/123098910
绝对路径:利用 urdf 文件生成 xml 文件时需要绝对地址,即初始 xml 文件使用绝对路径;
meshdir="/home/robot/DoorGym/world_generator/robot/meshes_walker/"
相对路径:xml 文件存在包含 (include) 关系时,包含和被包含的 xml 文件必须使用相对路径,且尽量放在同一文件夹下(参考)。
# 被包含文件
meshdir="/home/robot/DoorGym/world_generator/robot/meshes_walker/"
# 包含文件
<include file="../../robot/left_hand.xml"/>
在实际应用过程中,有些机器人为欠驱动关节,特别是机器人的灵巧手,较多为拉线式欠驱动配置。
以上内容主要参考: 官网文档 和 官方论坛 中欠驱动机器人和机械手配置。
<mujoco model="hand">
<tendon>
<fixed name="T_right_thumb">
<joint joint="right_thumb_j1" coef="1.0"/>
<joint joint="right_thumb_j2" coef="-1.0"/>
</fixed>
<fixed name="T_right_index">
<joint joint="right_index_j1" coef="1.0"/>
<joint joint="right_index_j2" coef="-1.5"/>
</fixed>
<fixed name="T_right_middle">
<joint joint="right_middle_j1" coef="1.0"/>
<joint joint="right_middle_j2" coef="-1.5"/>
</fixed>
<fixed name="T_right_ring">
<joint joint="right_ring_j1" coef="1.0"/>
<joint joint="right_ring_j2" coef="-1.5"/>
</fixed>
<fixed name="T_right_pinky">
<joint joint="right_pinky_j1" coef="1.0"/>
<joint joint="right_pinky_j2" coef="-1.25"/>
</fixed>
</tendon>
<equality>
<tendon name="E_right_thumb" tendon1="T_right_thumb"/>
<tendon name="E_right_index" tendon1="T_right_index"/>
<tendon name="E_right_middle" tendon1="T_right_middle"/>
<tendon name="E_right_ring" tendon1="T_right_ring"/>
<tendon name="E_right_pinky" tendon1="T_right_pinky"/>
</equality>
<actuator>
<position name="R_thumb_P" ctrllimited="true" kp="1.0" ctrlrange="0 1.00" joint="right_thumb_j1" />
<position name="R_index_P" ctrllimited="true" kp="1.0" ctrlrange="0 1.57" joint="right_index_j1" />
<position name="R_middle_P" ctrllimited="true" kp="1.0" ctrlrange="0 1.57" joint="right_middle_j1" />
<position name="R_ring_P" ctrllimited="true" kp="1.0" ctrlrange="0 1.57" joint="right_ring_j1" />
<position name="R_pinky_P" ctrllimited="true" kp="1.0" ctrlrange="0 1.57" joint="right_pinky_j1" />
</actuator>
</mujoco>
<mujoco model="hand">
<equality>
<joint name="ring_pinky_cpl" joint1="right_ring_j1" joint2="right_pinky_j1" polycoef="0 1.0 0 0 0"/>
</equality>
<actuator>
<position name="R_ring_P" ctrllimited="true" kp="1.0" ctrlrange="0 1.57" joint="right_ring_j1" />
</actuator>
</mujoco>
本文参考文档均以超链接形式在文中给出。
以上内容根据自己理解和实践所写,如有错误,请批评指正。