numpy , modern_robotics , urdfpy should be preinstalled.
pip install mr_urdf_loaderor
git clone https://github.com/tjdalsckd/mr_urdf_loader.git
cd mr_urdf_loader
pip install .To import the package, we recommend using
from mr_urdf_loader import loadURDF
urdf_name = "./test.urdf"
MR=loadURDF(urdf_name)
M = MR["M"]
Slist = MR["Slist"]
Mlist = MR["Mlist"]
Glist = MR["Glist"]
Blist = MR["Blist"]
cd tests/example/3DoF
python3 urdf_loader.pycd tests/example/3DoF
pip install pybullet
python3 sim.pycd tests/example/ur5
python3 ur5_sim.pyIt is possible to use the package locally without installation. Download and place the package in the working directory. Note that since the package is not installed, you need to move the package if the working directory is changed. Importing is still required before using.
In the case of PyBullet, if the final link in the URDF does not include an tag, the dynamics calculations will differ.
<link name="eef_link" />
Therefore, to ensure consistent dynamic behavior with the Modern Robotics library, even links with zero mass should explicitly include inertial information as follows:
<link name="eef_link">
<collision>
<geometry>
<box size="0.00 0.00 0.00"/>
</geometry>
<origin rpy="0 0 0" xyz="0.00 0 0"/>
</collision>
<inertial>
<mass value="0.0"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
</link>


