【学习】robosuite安装配置添加自定义机械臂教程
一、前言
我复现一些开源项目后(尤其是模仿学习相关)发现,特定任务的数据集异常难获取,其跟大模型领域或者之前的人工智能任务不同,机器人领域需要场景、任务、机器人设备都相对契合才能够作为自己的训练数据,这在小领域特定任务显然是不可能的,因此能够自己采集数据非常重要。
Robosuite是用于机器人研究的模块化模拟器,它涵盖了丰富多样的机器人实例支持,诸如人形机器人、自定义机器人组合,还包含复合控制器(像全身控制器等)、更多遥控设备选项,以及能够呈现出照片级逼真效果的渲染功能。
主要参考:
- https://zhuanlan.zhihu.com/p/607578201
- https://robosuite.ai/docs/installation.html#installing-on-windows
- https://blog.csdn.net/qq_41204464/article/details/145786608
- https://docs.google.com/document/d/1bSUKkpjmbKqWyV5Oc7_4VL4FGKAQZx8aWm_nvlmTVmE/edit?tab=t.0
二、部署
Robosuite本身支持源码安装和pip安装,如果需要长线开发,建议选择源码安装,如果只是简单使用,可以选择pip安装(更简单)。
这里我们先做源码教程
2.1 源码安装
这里我们需要你已经有了conda环境。
创建虚拟环境
conda create -n robosuite python=3.10
conda activate robosuite
下载项目
git clone https://github.com/ARISE-Initiative/robosuite.git
cd robosuite
安装依赖(国内镜像)
pip install -r requirements.txt -i https://pypi.tuna.tsinghua.edu.cn/simple
安装可选依赖(如OpenAI Gym 接口、由PyBullet提供支持的逆运动学控制器以及使用SpaceMouse设备的远程操作)
pip install -r requirements-extra.txt -i https://pypi.tuna.tsinghua.edu.cn/simple
2.2 pip安装
pip install robosuite
没了。。。就是这么简单,但是不建议,除非真的只是用一用已有的功能。
三、使用
3.1 基本指令
官方演示demo
python -m robosuite.demos.demo_random_action
运行后,首先选择环境
Here is a list of environments in the suite:
[0] Door
[1] Lift
[2] NutAssembly
[3] NutAssemblyRound
[4] NutAssemblySingle
[5] NutAssemblySquare
[6] PickPlace
[7] PickPlaceBread
[8] PickPlaceCan
[9] PickPlaceCereal
[10] PickPlaceMilk
[11] PickPlaceSingle
[12] Stack
[13] ToolHang
[14] TwoArmHandover
[15] TwoArmLift
[16] TwoArmPegInHole
[17] TwoArmTransport
[18] Wipe
不同环境下支持不同的机器人
[0] Baxter
[1] GR1ArmsOnly
[2] IIWA
[3] Jaco
[4] Kinova3
[5] Panda
[6] Sawyer
[7] SpotWithArmFloating
[8] Tiago
[9] UR5e
[10] XArm7
这里我选择了Door->Panda,即可得到帕金森的panda~(脚本主要目的是验证环境和模型)

3.2 调用api
robosuite提供了一组标准化的操作任务用于测试
参考:https://blog.csdn.net/qq_41204464/article/details/145786608
import numpy as np
import robosuite as suite
# 创建环境实例
env = suite.make(
env_name="Lift", # 任务名称,可以尝试其他任务,例如 "Stack" 或 "Door"
robots="Panda", # 使用的机器人类型,可以尝试其他机器人,例如 "Sawyer" 或 "Jaco"
has_renderer=True, # 是否启用屏幕渲染器(在屏幕上显示环境)
has_offscreen_renderer=False, # 是否启用离屏渲染器(用于生成图像等)
use_camera_obs=False, # 是否使用摄像头观察
)
# 重置环境(初始化环境状态)
obs = env.reset()
# 循环运行1000步
for i in range(1000):
action = np.random.randn(*env.action_spec[0].shape) * 0.1 # 生成随机动作,动作幅度乘以0.1限制动作大小
obs, reward, done, info = env.step(action) # 在环境中执行动作,获取观察值、奖励、是否完成等信息
env.render() # 在屏幕上渲染当前环境状态
# 检查是否需要重置环境
if done:
print(f"Episode ended at step {i}. Resetting environment.")
obs = env.reset()
效果

3.3 键盘控制机械臂
robosuite中给出了很多调用api的demo,在robosuite\demos下,这里我演示一下键盘控制机械臂在lift场景中抓取方块的命令
python robosuite\demos\demo_device_control.py --robots panda --environment Lift

四、导入自定义机器人
用了两天时间,终于摸索清楚添加自定义机器人、机械臂最少需要添加的文件有哪些。。网上没有完整教程,这应该算是全网第一份了。
我添加的是法奥fr5机械臂,主要参考ur机械臂,我的具体型号是fairino_fr5,后面不再赘述。
需要:
robosuite/models/assets/robots/fairino_fr5/robot.xml- 物理定义,机械臂的描述文件,mujoco MJCF格式
- 至少包括joint、geom、actuator、camera
robosuite/models/assets/robots/fairino_fr5/meshes/base_link.STL等- 几何模型
robosuite\controllers\config\robots\default_fairinofr5.json- 运动控制参数
- 阻尼、控制类型、参考坐标系
robosuite/models/robots/manipulators/fairinofr5_robot.py- 机械臂类,用于给定初始位姿、默认夹爪、环境、映射配置文件
robosuite/robots/__init__.py- 类与机械臂名称关联映射
robosuite/models/robots/manipulators/__init__.py- 入口
4.1 robot.xml
4.1.1 基础准备
参考:https://docs.google.com/document/d/1bSUKkpjmbKqWyV5Oc7_4VL4FGKAQZx8aWm_nvlmTVmE/edit?tab=t.0
robosuit支持的设备在robosuite\robosuite\models\assets\robots

-
在
robosuite\models\assets\robots中创建fairino_fr5文件夹 -
在
robosuite\models\assets\robots\fairino_fr5目录下创建meshes文件夹 -
将机械臂STL文件放入meshes中
-
mujoco导入urdf,转换xml
- 转换前,须在urdf的robot标签下添加:
<mujoco>
<compiler
meshdir="meshes/"
balanceinertia="true"
discardvisual="false" />
</mujoco>

- 得到mjmodel.xml
4.1.2 微调
先构建一个xml框架,符合robosuite的模块化加载方式。
在robosuite\models\assets\robots\fairino_fr5中创建robot.xml文件
<mujoco model="fairino_fr5">
<compiler angle="radian"/>
<actuator>
<motor ctrllimited="true" ctrlrange="-150 150" joint="j1" name="torq_j1"/>
<motor ctrllimited="true" ctrlrange="-150 150" joint="j2" name="torq_j2"/>
<motor ctrllimited="true" ctrlrange="-100 100" joint="j3" name="torq_j3"/>
<motor ctrllimited="true" ctrlrange="-50 50" joint="j4" name="torq_j4"/>
<motor ctrllimited="true" ctrlrange="-50 50" joint="j5" name="torq_j5"/>
<motor ctrllimited="true" ctrlrange="-30 30" joint="j6" name="torq_j6"/>
</actuator>
<asset>
<mesh name="base_link" file="meshes/base_link.STL"/>
<mesh name="shoulder_link" file="meshes/shoulder_link.STL"/>
<mesh name="upperarm_link" file="meshes/upperarm_link.STL"/>
<mesh name="forearm_link" file="meshes/forearm_link.STL"/>
<mesh name="wrist1_link" file="meshes/wrist1_link.STL"/>
<mesh name="wrist2_link" file="meshes/wrist2_link.STL"/>
<mesh name="wrist3_link" file="meshes/wrist3_link.STL"/>
</asset>
<worldbody>
<body name="base" pos="0 0 0">
</body>
</worldbody>
<actuator>
</actuator>
</mujoco>
- 将mjmodell.xml中的worldbody补充到robot.xml的worldbody/body下
- 要保证所有geom都有name
完整的worldbody:
<worldbody>
<body name="base" pos="0 0 0">
<!-- robot view -->
<camera mode="fixed" name="robotview" pos="1.0 0 0.4" quat="0.653 0.271 0.271 0.653"/>
<inertial diaginertia="0 0 0" mass="0" pos="0 0 0"/>
<!-- mount attached here -->
<body name="fixed_base_link" pos="0 0 0">
<site name="right_center" pos="0 0 0.05" size="0.01" rgba="1 0.3 0.3 1" group="2"/>
<geom type="mesh" mesh="base_link" name="base_geom"/>
<geom type="mesh" mesh="base_link" group="1" contype="0" conaffinity="0" rgba="0.7 0.7 0.7 1"/>
<body name="shoulder_link" pos="0 0 0.01">
<inertial pos="5.0029e-07 -0.0040922 0.14629" quat="0.999588 0.0287044 7.54149e-06 -1.58789e-05" mass="4.3771" diaginertia="0.010731 0.0104154 0.00817191"/>
<joint name="j1" pos="0 0 0" axis="0 0 1" range="-3.0543 3.0543" ref="3.14159" limited="true" />
<geom type="mesh" mesh="shoulder_link" name="shoulder_geom" />
<geom type="mesh" mesh="shoulder_link" group="1" contype="0" conaffinity="0" rgba="1 0 0 1"/>
<body name="upperarm_link" pos="0 0 0.152" quat="0.707105 0.707108 0 0">
<inertial pos="-0.2125 -5.7643e-09 0.1346" quat="0.5 0.5 0.5 0.5" mass="14.458" diaginertia="0.4559 0.44974 0.028392"/>
<joint name="j2" pos="0 0 0" axis="0 0 1" range="-4.6251 1.4835" limited="true" />
<geom type="mesh" mesh="upperarm_link" name="upperarm_geom"/>
<geom type="mesh" mesh="upperarm_link" group="1" contype="0" conaffinity="0" rgba="0 1 0 1"/>
<body name="forearm_link" pos="-0.425 0 0">
<inertial pos="-0.18793 -8.4503e-07 0.0066357" quat="0.510607 0.489172 0.489196 0.510568" mass="7.6737" diaginertia="0.16971 0.168834 0.00821541"/>
<joint name="j3" pos="0 0 0" axis="0 0 1" range="-2.8274 2.8274" limited="true" />
<geom type="mesh" mesh="forearm_link" name="forearm_geom"/>
<geom type="mesh" mesh="forearm_link" group="1" contype="0" conaffinity="0" rgba="0 0 1 1"/>
<body name="wrist1_link" pos="-0.39501 0 0">
<inertial pos="4.98e-07 -0.003754 0.097155" quat="0.736149 0.676819 -6.33095e-05 7.15237e-05" mass="1.6266" diaginertia="0.00216 0.00199337 0.00154233"/>
<joint name="j4" pos="0 0 0" axis="0 0 1" range="-4.6251 1.4835" limited="true" />
<geom type="mesh" mesh="wrist1_link" name="wrist1_geom"/>
<geom type="mesh" mesh="wrist1_link" group="1" contype="0" conaffinity="0" rgba="1 1 1 1"/>
<body name="wrist2_link" pos="0 0 0.1021" quat="0.707105 0.707108 0 0">
<inertial pos="-4.5588e-07 0.0038617 0.098257" quat="0.68712 0.726544 0.000128667 -0.000114125" mass="1.5812" diaginertia="0.0020612 0.00195889 0.00144611"/>
<joint name="j5" pos="0 0 0" axis="0 0 1" range="-3.0543 3.0543" limited="true" />
<geom type="mesh" mesh="wrist2_link" name="wrist2_geom"/>
<geom type="mesh" mesh="wrist2_link" group="1" contype="0" conaffinity="0" rgba="0.7 0.7 0.7 1"/>
<body name="wrist3_link" pos="0 0 0.102" quat="0.707105 -0.707108 0 0">
<inertial pos="7.7496e-05 1.7751e-05 0.076122" quat="7.93213e-05 0.706804 0.00108234 0.707408" mass="0.52542" diaginertia="0.00041605 0.00027839 0.00027721"/>
<joint name="j6" pos="0 0 0" axis="0 0 1" range="-3.0543 3.0543" limited="true" />
<geom type="mesh" mesh="wrist3_link" name="wrist3_geom"/>
<geom type="mesh" mesh="wrist3_link" group="1" contype="0" conaffinity="0" rgba="0.7 0.7 0.7 1"/>
<body name="right_hand" pos="0 0 0.05" quat="0 0 0 1">
<camera mode="fixed" name="eye_in_hand" pos="0.05 0 0" quat="0 0.707107 0 0.707107" fovy="75"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
这里创建完成后,可以先用mujoco加载一下进行验证。

[!IMPORTANT]
有两点需要十分注意
- group
- mujoco会为geom添加默认的灰色用于显示
- 但robosuite中不会,其通过group属性将geom分成了三组
- group 0
- 碰撞组,用于物理计算
- group 1
- 视觉组,渲染展示
- group 2
- 逻辑控制,如抓取点、参考点、相机挂载点
- 因此,如果你将mujoco中能够正常显示的灰色模型拿进来,那一般来说是看不到模型, 你会认为自己添加失败了。。实际上是变成了透明,需要手动添加颜色
- ref
- 细心的话应该能看到我
<joint name="j1" ref="3.14159" />- 这是因为法奥模型的全0状态默认是沿x轴正方向“躺平”,与ur相反
- 导致导入后其是背对桌子的(这一点在其他项目中,如act,会产生极大困扰)
- 因此需要通过ref逻辑上旋转180°规避
- 如果通过init_qpos调整,会导致限位不够
4.2 controller config文件
robosuite\controllers\config\robots\default_fairinofr5.json
这里这个文件我直接拷贝自ur5e,没什么好调整的,如果你做非抓取任务,这里需要添加其他文件,我这是抓取任务。
{
"type": "BASIC",
"body_parts": {
"arms": {
"right": {
"type": "OSC_POSE",
"input_max": 1,
"input_min": -1,
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
"kp": 150,
"damping_ratio": 1,
"impedance_mode": "fixed",
"kp_limits": [0, 300],
"damping_ratio_limits": [0, 10],
"position_limits": null,
"orientation_limits": null,
"uncouple_pos_ori": true,
"input_type": "delta",
"input_ref_frame": "base",
"interpolation": null,
"ramp_ratio": 0.2,
"gripper": {
"type": "GRIP"
}
}
}
}
}
4.3 Python 包装类
- 找到
robosuite/models/robots/manipulators文件夹 - 创建fairino_fr5_robot.py
import numpy as np
from robosuite.models.robots.manipulators.manipulator_model import ManipulatorModel
from robosuite.utils.mjcf_utils import xml_path_completion
class FairinoFR5(ManipulatorModel):
arms = ["right"]
def __init__(self, idn=0):
super().__init__(xml_path_completion("robots/fairino_fr5/robot.xml"), idn=idn)
@property
def default_base(self):
return "RethinkMount"
@property
def default_gripper(self):
return {"right": "Robotiq85Gripper"}
@property
def default_controller_config(self):
return {"right": "default_fairino_fr5"}
@property
def arm_type(self):
return "single"
@property
def init_qpos(self):
return np.array([-0.470, -1.735, 2.480, -2.275, -1.590, -1.991])
@property
def base_xpos_offset(self):
return {
"bins": (-0.5, -0.1, 0),
"empty": (-0.6, 0, 0),
"table": lambda table_length: (-0.16 - table_length / 2, 0, 0),
}
@property
def top_offset(self):
# 用于计算机器人上方安全距离的偏移
return np.array((0, 0, 1.0))
@property
def _horizontal_radius(self):
return 0.5
- default_base
- 默认基座
- 如果想放在地上,就填写"NullMount"
- default_gripper
- 默认夹爪
robosuite\models\grippers\__init__.py描述了支持的夹爪
4.4 init
到这步表明已经填好了其他配置文件,需要两个__init___.py文件引入。
robosuite\robots\__init__.py- ROBOT_CLASS_MAPPING中添加
"FairinoFR5": FixedBaseRobot
robosuite\models\robots\manipulators\__init__.pyfrom .fairinofr5_robot import FairinoFR5
展示
使用键盘操作控制法奥机械臂执行抓取任务
python robosuite\demos\demo_device_control.py --robots FairinoFR5 --environment Lift


浙公网安备 33010602011771号