Registering a New Custom SDF
Hi MuJoCo community,
I'm a research assistant and I'm trying to use MuJoCo for assembly tasks. Specifically, I want to create non-convex collision meshes to facilitate inserting let's say a USB cable into its female connector. My current understanding is that this can be done using SDF plugins in MuJoCo. While and read and I believe understood the current documentation I seem to be encountering a small road block in registering my custom plugin.
My current progress is as follows:
- I am unable to locate the
sdf/plugin directory on my local machine when MuJoCo was installed throughpipI therefore-
Cloned the MuJoCo repo form GitHub
-
Navigated to the sdf folder
-
added new
.hand.ccfiles calledtest.handtest.cc. Both of these hold the same code astorus.ccandtorus.h, except all instances ofToruswas replaced withTest. -
I navigated to
register.ccand added my pluginmodified `register.cc` ``` c#include "bolt.h" #include "bowl.h" #include "gear.h" #include "nut.h" #include "torus.h" #include "sdflib.h" #include "test.h" namespace mujoco::plugin::sdf { mjPLUGIN_LIB_INIT { Bolt::RegisterPlugin(); Bowl::RegisterPlugin(); Gear::RegisterPlugin(); Nut::RegisterPlugin(); Torus::RegisterPlugin(); SdfLib::RegisterPlugin(); // I added this line Test::RegisterPlugin(); } } // namespace mujoco::plugin::sdf ``` </details> -
and added the new files to the
CMakeLists.txtfilemodified `CMakeLists.txt` ``` CMakeLists... set(MUJOCO_SDF_SRCS sdf.cc sdf.h bolt.cc ... sdflib.h torus.cc torus.h # I added these lines test.cc test.h ) ... ``` </details> -
Having done so, I navigate to the root directory of the repo and build and compile i.e.
cmake -Bbuild && cd build && make. When compiling I get output like so:compile output ``` bash... [ 30%] Building CXX object plugin/sdf/CMakeFiles/sdf.dir/nut.cc.o [ 30%] Building CXX object plugin/sdf/CMakeFiles/sdf.dir/sdflib.cc.o [ 30%] Building CXX object plugin/sdf/CMakeFiles/sdf.dir/torus.cc.o [ 30%] Building CXX object plugin/sdf/CMakeFiles/sdf.dir/test.cc.o [ 30%] Linking CXX shared library ../../lib/libsdf.so [ 30%] Built target sdf [ 33%] Built target glfw [ 34%] Built target platform_ui_adapter ... ``` </details> -
which seems like it includes my newly added plugin
-
- I now create a new mujoco project and where which include the following
MuJoCo Python code
``` python import time
import mujoco
import mujoco.viewer
m = mujoco.MjModel.from_xml_path('/path/to/torus.xml')
d = mujoco.MjData(m)
with mujoco.viewer.launch_passive(m, d) as viewer:
start = time.time()
while viewer.is_running() and time.time():
step_start = time.time()
mujoco.mj_step(m, d)
# Pick up changes to the physics state, apply perturbations, update options from GUI.
viewer.sync()
# Rudimentary time keeping, will drift relative to wall clock.
time_until_next_step = m.opt.timestep - (time.time() - step_start)
if time_until_next_step > 0:
time.sleep(time_until_next_step)
```
`XML` file from the MuJoCo repo, but modified
``` XML<mujoco>
<extension>
<!-- <plugin plugin="mujoco.sdf.torus"> -->
<plugin plugin="mujoco.sdf.test">
<instance name="torus">
<config key="radius1" value="0.35"/>
<config key="radius2" value="0.15"/>
</instance>
</plugin>
</extension>
<asset>
<mesh name="torus">
<plugin instance="torus"/>
</mesh>
</asset>
<option sdf_iterations="10" sdf_initpoints="40"/>
<include file="scene.xml"/>
<default>
<geom solref="0.01 1" solimp=".95 .99 .0001" friction="0.1"/>
</default>
<worldbody>
<body pos="-1 0 3.8">
<freejoint/>
<geom type="sdf" mesh="torus" rgba=".2 .2 .8 1">
<plugin instance="torus"/>
</geom>
</body>
<body pos="-1 0 3.4">
<freejoint/>
<geom type="sdf" mesh="torus" rgba=".2 .8 .2 1">
<plugin instance="torus"/>
</geom>
</body>
<body pos="-1 0 3">
<freejoint/>
<geom type="sdf" mesh="torus" rgba=".8 .2 .2 1">
<plugin instance="torus"/>
</geom>
</body>
<body pos="0 0 2">
<geom type="cylinder" size=".1" fromto="1 0 -1 -1 0 1"/>
</body>
<body pos="0 0 2">
<geom type="cylinder" size=".5" fromto="1.2 0 -1.2 1 0 -1"/>
</body>
<light name="left" pos="-2 0 7" cutoff="80"/>
<light name="right" pos="2 0 7" cutoff="80"/>
</worldbody>
</mujoco>
```
- When running this simulation I however get the following error:
Traceback (most recent call last):
File "main.py", line 10, in <module>
m = mujoco.MjModel.from_xml_path('/path/to/torus.xml')
ValueError: XML Error: unknown plugin 'mujoco.sdf.test'
Element 'plugin', line 5
All feedback and/or ideas for how I could progress/solve this problem of mine are very much appreciated!
Is MUJOCO_PATH pointing to the right mujoco, i.e. the one you built?