这是本文档旧的修订版!
单个python文件实现pybullet在arx5上的双臂仿真
安装python环境
pip install pybullet numpy
准备代码目录结构如下:
.
├── arx5
│ ├── apple.urdf
│ ├── arx5.urdf
│ ├── meshes
│ │ ├── X5
│ │ │ ├── link1.STL
│ │ │ ├── link2.STL
│ │ │ ├── link3.STL
│ │ │ ├── link4.STL
│ │ │ ├── link5.STL
│ │ │ └── link6.STL
│ │ └── base_link.STL
│ └── run-sim.py
└── main.py
其中STL文件参考:
URDF文件参考
- apple.URFDF 文件是用AI生成的:
<?xml version="1.0"?>
<robot name="apple">
<!-- 苹果主体(球体近似) -->
<link name="apple_body">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.08"/> <!-- 苹果直径约16cm,半径0.08m -->
</geometry>
<material name="red_green">
<color rgba="0.8 0.2 0.2 1.0"/> <!-- 红色为主色 -->
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.08"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.2"/> <!-- 苹果重量约200g -->
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
</link>
<!-- 苹果柄(圆柱体) -->
<link name="apple_stem">
<visual>
<origin xyz="0 0 0.08" rpy="1.5708 0 0"/> <!-- 沿Y轴旋转90度 -->
<geometry>
<cylinder length="0.03" radius="0.005"/> <!-- 柄长3cm,半径0.5cm -->
</geometry>
<material name="brown">
<color rgba="0.5 0.25 0.1 1.0"/> <!-- 棕色 -->
</material>
</visual>
<collision>
<origin xyz="0 0 0.08" rpy="1.5708 0 0"/>
<geometry>
<cylinder length="0.03" radius="0.005"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0.08" rpy="0 0 0"/>
<mass value="0.01"/> <!-- 柄重量约10g -->
<inertia ixx="0.00001" ixy="0" ixz="0" iyy="0.00001" iyz="0" izz="0.00001"/>
</inertial>
</link>
<!-- 苹果叶子(平面近似) -->
<link name="apple_leaf">
<visual>
<origin xyz="0.02 0 0.1" rpy="0 0 0"/> <!-- 稍微偏移以贴近柄 -->
<geometry>
<box size="0.04 0.02 0.001"/> <!-- 叶子宽4cm,长2cm,厚0.1cm -->
</geometry>
<material name="green">
<color rgba="0.0 0.5 0.0 1.0"/> <!-- 绿色 -->
</material>
</visual>
<collision>
<origin xyz="0.02 0 0.1" rpy="0 0 0"/>
<geometry>
<box size="0.04 0.02 0.001"/>
</geometry>
</collision>
<inertial>
<origin xyz="0.02 0 0.1" rpy="0 0 0"/>
<mass value="0.005"/> <!-- 叶子重量约5g -->
<inertia ixx="0.000001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.000001"/>
</inertial>
</link>
<!-- 连接苹果主体与柄 -->
<joint name="stem_to_body" type="fixed">
<parent link="apple_body"/>
<child link="apple_stem"/>
<origin xyz="0 0 0.08" rpy="0 0 0"/>
</joint>
<!-- 连接柄与叶子 -->
<joint name="leaf_to_stem" type="fixed">
<parent link="apple_stem"/>
<child link="apple_leaf"/>
<origin xyz="0.02 0 0.03" rpy="0 0 0"/> <!-- 叶子连接到柄末端 -->
</joint>
</robot>
评论