google-deepmind / mujoco

Multi-Joint dynamics with Contact. A general purpose physics simulator.
https://mujoco.org
Apache License 2.0
7.84k stars 783 forks source link

Segmentation Fault when using plugin for mjSpec #1903

Closed LilianLaporte closed 1 month ago

LilianLaporte commented 1 month ago

Hello,

I am trying to spawn an object (similar as the one in the xml file) via mjSpec. However, I am using a plugin (mujoco.elasticity.cable) and I get a Segmentation Fault error when I want to set it up with the spec. On top of that, when I am using the debugger and checking what is inside the plugin attribute of the body2, the program crashes (cf picture). So I guess something is wrong concerning this plugin. I am also wondering if I am setting the plugin in a correct way or if I should do something else. If not, how should I set it up such that I get the same as the one in the xml file?

Picture of crash when accessing plugin in body2

Screenshot from 2024-08-14 16-42-51

xml file ```xml ```
python code ```python import sys, os import time # Add the parent directory to sys.path sys.path.append(os.path.abspath(os.path.join(os.path.dirname(__file__), '..'))) import mujoco import mujoco.viewer def display_video(frames, videoname='animation.mp4', framerate=30): """Display a list of frames as a video. Args: frames (list): list of frames to display. videoname (str, optional): name of the video. Defaults to 'animation.mp4'. framerate (int, optional): # frames per second. Defaults to 30. """ height, width, _ = frames[0].shape dpi = 10 orig_backend = matplotlib.get_backend() matplotlib.use('Agg') # Switch to headless 'Agg' to inhibit figure rendering. fig, ax = plt.subplots(1, 1, figsize=(width / dpi, height / dpi), dpi=dpi) matplotlib.use(orig_backend) # Switch back to the original backend. ax.set_axis_off() ax.set_aspect('equal') ax.set_position([0, 0, 1, 1]) im = ax.imshow(frames[0]) def update(frame): im.set_data(frame) return [im] interval = 1000/framerate anim = animation.FuncAnimation(fig=fig, func=update, frames=frames, interval=interval, blit=True, repeat=False) # return HTML(anim.to_html5_video()) # Save as MP4 anim.save(videoname, writer='ffmpeg', fps=framerate) plt.close(fig) def main(): spec = mujoco.MjSpec() spec.from_file("src/rebar_mujoco/environments/xml_files/mujoco.xml") model = spec.compile() data = mujoco.MjData(model) framerate = 40 # (Hz) timestep = 0.001 # (seconds) duration = 3 # (seconds) width, height = 500, 500 renderer = mujoco.Renderer(model, height=height, width=width) video_name = "src/rebar_mujoco/tests/tmp/test_mjSpec2.mp4" scene_option = mujoco.MjvOption() frames = [] frame_count = 0 camera = mujoco.MjvCamera() mujoco.mjv_defaultFreeCamera(model, camera) camera.distance = 2.5 camera.elevation = -20 camera.lookat = (0, 0, 0.5) add_body_time = 0.2 # seconds CHANGE THIS TO 2 SEC TO SEE THE DIFFERENCE add_body = False z_pos_vec = [] nb_step = 0 while nb_step*timestep < duration: mujoco.mj_step(model, data) if nb_step*timestep> add_body_time and not add_body: print("Adding body") add_body = True ### Uncomment section below to see the bug ### # plugin2_0 = spec.add_plugin() # plugin2_0.instance_name = "compositestirrup0" # plugin2_0.active = 1 ############################################## body2 = spec.worldbody.add_body() body2.name = "stirrup2" body2.pos = [0.5, 0, 2] # body2.quat = [ 0, 0, 0.7071068, 0.7071068 ] body2.quat = [ 1, 0, 0, 0 ] body2.mass = 1 body2.inertia = [0.001, 0.001, 0.001] joint = body2.add_joint() joint.type = mujoco.mjtJoint.mjJNT_FREE geom00 = body2.add_geom() geom00.type = mujoco.mjtGeom.mjGEOM_CAPSULE geom00.size = [0.005, 0.2825, 0] geom00.pos = [0, 0, 0] geom00.quat = [1, 0., 0., 0.] geom00.name = "stirrup2G0" geom00.rgba = [0.8, 0.2, 0.1, 1] # Recompile model and data while maintaining the state. model, data = spec.recompile(model, data) renderer.close() renderer = mujoco.Renderer(model, height=height, width=width) if frame_count < nb_step*timestep * framerate: renderer.update_scene(data, camera=camera, scene_option=scene_option) frame = renderer.render() frames.append(frame) frame_count += 1 display_video(frames, video_name, framerate) print(f"Video saved at {video_name}") if __name__ == '__main__': main() ```

Context:

andy-Chien commented 1 week ago

Hi @LilianLaporte Are you fix this yet? I got same problem, but I'm progrem in c++. The error from my side is because I didn't load plugins before loading xml model. So I load all built-in plugin before init the spec, and the problem solved. I hope this would be helpful to you.