mujoco-py icon indicating copy to clipboard operation
mujoco-py copied to clipboard

Segmentation fault (core dumped) from using PID controller plugin and keyframes simultaneously

Open vmstavens opened this issue 11 months ago • 0 comments

Describe the bug I have a Python 3.9.5 virtual environment running MuJoCo (3.1.2) in my setup on Ubuntu 20.04 with a UR5e from mujoco_mangerie where I am trying to manipulate a soft body using a Hand-E gripper. Each UR5e actuator is being controlled using the new PID controllers introduced in version 3.1.0 (December 12, 2023). When running this simulation I would like to save and load different states of my simulation, I can understand on the documentation that keyframes are one of the ways to solve this. I like this approach as it enables me to read and changes parameters in the keyframes xml.

The problem appears to be a clash between the new PID controller plugin and loading in keyframes, as when both are included I simply get a Segmentation fault (core dumped).

I have attempted to isolate the problem with just the UR5e manipulator in the scene (along with axes and lights), but the problem seems to persist.

To Reproduce While reproducing the error might take a little setting up wrt. the meshes of the manipulator, I have here included my scene xml as generated form Save xml

Save xml button result ```
<compiler angle="radian"/>

<option impratio="100" gravity="0 0 -9.82" integrator="RK4" cone="elliptic"/>

<visual>

<global azimuth="120" elevation="-20"/>

<headlight diffuse="0.6 0.6 0.6" specular="0 0 0"/>

<rgba haze="0.15 0.25 0.35 1"/>

</visual>

<default class="main">

<default class="ur5e">

<material shininess="0.25"/>

<joint range="-6.28319 6.28319" armature="0.1"/>

<site size="0.001 0.005 0.005" group="4" rgba="0.5 0.5 0.5 0.3"/>

<general ctrlrange="-6.2831 6.2831" forcerange="-150 150" biastype="affine" gainprm="2000 0 0 0 0 0 0 0 0 0" biasprm="0 -2000 -400 0 0 0 0 0 0 0"/>

<default class="size3">

<site size="0.005 0.005 0.005" group="0" rgba="0.5 0.5 0.5 1"/>

<default class="size3_limited">

<joint range="-3.1415 3.1415"/>

<general ctrlrange="-3.1415 3.1415"/>

</default>

</default>

<default class="size1">

<site size="0.005 0.005 0.005" group="0" rgba="0.5 0.5 0.5 1"/>

<general forcerange="-28 28" gainprm="500 0 0 0 0 0 0 0 0 0" biasprm="0 -500 -100 0 0 0 0 0 0 0"/>

</default>

<default class="visual">

<geom type="mesh" contype="0" conaffinity="0" group="2"/>

<site size="0.005 0.005 0.005" group="0" rgba="0.5 0.5 0.5 1"/>

</default>

<default class="collision">

<geom type="capsule" group="3"/>

<site size="0.005 0.005 0.005" group="0" rgba="0.5 0.5 0.5 1"/>

<default class="eef_collision">

<geom type="cylinder"/>

</default>

</default>

</default>

</default>

<extension>

<plugin plugin="mujoco.pid">

<instance name="shoulder_pan_joint_position_controller">

<config key="kp" value="500.0"/>

<config key="ki" value="0.01"/>

<config key="kd" value="50.0"/>

</instance>

<instance name="shoulder_lift_joint_position_controller">

<config key="kp" value="500.0"/>

<config key="ki" value="100.0"/>

<config key="kd" value="30.0"/>

</instance>

<instance name="elbow_joint_position_controller">

<config key="kp" value="10000.0"/>

<config key="ki" value="0.01"/>

<config key="kd" value="50.0"/>

</instance>

<instance name="wrist_1_joint_position_controller">

<config key="kp" value="200.0"/>

<config key="ki" value="10.0"/>

<config key="kd" value="20.0"/>

</instance>

<instance name="wrist_2_joint_position_controller">

<config key="kp" value="100.0"/>

<config key="ki" value="0.1"/>

<config key="kd" value="10.0"/>

</instance>

<instance name="wrist_3_joint_position_controller">

<config key="kp" value="100.0"/>

<config key="ki" value="0.1"/>

<config key="kd" value="10.0"/>

</instance>

</plugin>

</extension>

<asset>

<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="3072"/>

<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>

<material name="black" class="ur5e" rgba="0.033 0.033 0.033 1"/>

<material name="jointgray" class="ur5e" rgba="0.278 0.278 0.278 1"/>

<material name="linkgray" class="ur5e" rgba="0.82 0.82 0.82 1"/>

<material name="urblue" class="ur5e" rgba="0.49 0.678 0.8 1"/>

<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>

<mesh name="base_0" file="../ur5e/assets/base_0.obj"/>

<mesh name="base_1" file="../ur5e/assets/base_1.obj"/>

<mesh name="shoulder_0" file="../ur5e/assets/shoulder_0.obj"/>

<mesh name="shoulder_1" file="../ur5e/assets/shoulder_1.obj"/>

<mesh name="shoulder_2" file="../ur5e/assets/shoulder_2.obj"/>

<mesh name="upperarm_0" file="../ur5e/assets/upperarm_0.obj"/>

<mesh name="upperarm_1" file="../ur5e/assets/upperarm_1.obj"/>

<mesh name="upperarm_2" file="../ur5e/assets/upperarm_2.obj"/>

<mesh name="upperarm_3" file="../ur5e/assets/upperarm_3.obj"/>

<mesh name="forearm_0" file="../ur5e/assets/forearm_0.obj"/>

<mesh name="forearm_1" file="../ur5e/assets/forearm_1.obj"/>

<mesh name="forearm_2" file="../ur5e/assets/forearm_2.obj"/>

<mesh name="forearm_3" file="../ur5e/assets/forearm_3.obj"/>

<mesh name="wrist1_0" file="../ur5e/assets/wrist1_0.obj"/>

<mesh name="wrist1_1" file="../ur5e/assets/wrist1_1.obj"/>

<mesh name="wrist1_2" file="../ur5e/assets/wrist1_2.obj"/>

<mesh name="wrist2_0" file="../ur5e/assets/wrist2_0.obj"/>

<mesh name="wrist2_1" file="../ur5e/assets/wrist2_1.obj"/>

<mesh name="wrist2_2" file="../ur5e/assets/wrist2_2.obj"/>

<mesh name="wrist3" file="../ur5e/assets/wrist3.obj"/>

</asset>

<worldbody>

<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>

<geom name="x-aixs" size="0.01 0.5" pos="0.5 0 0" quat="0.707107 0 -0.707107 0" type="cylinder" contype="0" conaffinity="0" group="2" rgba="1 0 0 1"/>

<geom name="y-aixs" size="0.01 0.5" pos="0 0.5 0" quat="0.707107 0.707107 0 0" type="cylinder" contype="0" conaffinity="0" group="2" rgba="0 1 0 1"/>

<geom name="z-aixs" size="0.01 0.5" pos="0 0 0.5" quat="0 1 0 0" type="cylinder" contype="0" conaffinity="0" group="2" rgba="0 0 1 1"/>

<light name="spotlight" target="wrist_2_link" pos="0 -1 2" dir="0 0 -1" mode="targetbodycom"/>

<light pos="0 0 1.5" dir="0 0 -1" directional="true"/>

<body name="base" childclass="ur5e" quat="0.707107 0 0 0.707107">

<inertial pos="0 0 0" mass="4" diaginertia="0.00443333 0.00443333 0.0072"/>

<geom class="visual" material="black" mesh="base_0"/>

<geom class="visual" material="jointgray" mesh="base_1"/>

<body name="shoulder_link" pos="0 0 0.163">

<inertial pos="0 0 0" mass="3.7" diaginertia="0.0102675 0.0102675 0.00666"/>

<joint name="ur5e_shoulder_pan_joint" class="size3" pos="0 0 0" axis="0 0 1"/>

<geom class="visual" material="urblue" mesh="shoulder_0"/>

<geom class="visual" material="black" mesh="shoulder_1"/>

<geom class="visual" material="jointgray" mesh="shoulder_2"/>

<geom class="collision" size="0.06 0.06" pos="0 0 -0.04"/>

<body name="upper_arm_link" pos="0 0.138 0" quat="0.707107 0 0.707107 0">

<inertial pos="0 0 0.2125" mass="8.393" diaginertia="0.133886 0.133886 0.0151074"/>

<joint name="ur5e_shoulder_lift_joint" class="size3" pos="0 0 0" axis="0 1 0"/>

<geom class="visual" material="linkgray" mesh="upperarm_0"/>

<geom class="visual" material="black" mesh="upperarm_1"/>

<geom class="visual" material="jointgray" mesh="upperarm_2"/>

<geom class="visual" material="urblue" mesh="upperarm_3"/>

<geom class="collision" size="0.06 0.06" pos="0 -0.04 0" quat="0.707107 0.707107 0 0"/>

<geom class="collision" size="0.05 0.2" pos="0 0 0.2"/>

<body name="forearm_link" pos="0 -0.131 0.425">

<inertial pos="0 0 0.196" mass="2.275" diaginertia="0.0311796 0.0311796 0.004095"/>

<joint name="ur5e_elbow_joint" class="size3_limited" pos="0 0 0" axis="0 1 0"/>

<geom class="visual" material="urblue" mesh="forearm_0"/>

<geom class="visual" material="linkgray" mesh="forearm_1"/>

<geom class="visual" material="black" mesh="forearm_2"/>

<geom class="visual" material="jointgray" mesh="forearm_3"/>

<geom class="collision" size="0.055 0.06" pos="0 0.08 0" quat="0.707107 0.707107 0 0"/>

<geom class="collision" size="0.038 0.19" pos="0 0 0.2"/>

<body name="wrist_1_link" pos="0 0 0.392" quat="0.707107 0 0.707107 0">

<inertial pos="0 0.127 0" mass="1.219" diaginertia="0.0025599 0.0025599 0.0021942"/>

<joint name="ur5e_wrist_1_joint" class="size1" pos="0 0 0" axis="0 1 0"/>

<geom class="visual" material="black" mesh="wrist1_0"/>

<geom class="visual" material="urblue" mesh="wrist1_1"/>

<geom class="visual" material="jointgray" mesh="wrist1_2"/>

<geom class="collision" size="0.04 0.07" pos="0 0.05 0" quat="0.707107 0.707107 0 0"/>

<body name="wrist_2_link" pos="0 0.127 0">

<inertial pos="0 0 0.1" mass="1.219" diaginertia="0.0025599 0.0025599 0.0021942"/>

<joint name="ur5e_wrist_2_joint" class="size1" pos="0 0 0" axis="0 0 1"/>

<geom class="visual" material="black" mesh="wrist2_0"/>

<geom class="visual" material="urblue" mesh="wrist2_1"/>

<geom class="visual" material="jointgray" mesh="wrist2_2"/>

<geom class="collision" size="0.04 0.06" pos="0 0 0.04"/>

<geom class="collision" size="0.04 0.04" pos="0 0.02 0.1" quat="0.707107 0.707107 0 0"/>

<body name="wrist_3_link" pos="0 0 0.1">

<inertial pos="0 0.0771683 0" quat="0.707107 0 0 0.707107" mass="0.1889" diaginertia="0.000132134 9.90863e-05 9.90863e-05"/>

<joint name="ur5e_wrist_3_joint" class="size1" pos="0 0 0" axis="0 1 0"/>

<geom class="visual" material="linkgray" mesh="wrist3"/>

<geom class="eef_collision" size="0.04 0.02" pos="0 0.08 0" quat="0.707107 0.707107 0 0"/>

<site name="attachment_site" pos="0 0.1 0" quat="-0.707107 0.707107 0 0"/>

</body>

</body>

</body>

</body>

</body>

</body>

</body>

</worldbody>

<actuator>

<plugin name="ur5e_shoulder_pan" joint="ur5e_shoulder_pan_joint" instance="shoulder_pan_joint_position_controller"/>

<plugin name="ur5e_shoulder_lift" joint="ur5e_shoulder_lift_joint" instance="shoulder_lift_joint_position_controller"/>

<plugin name="ur5e_elbow" joint="ur5e_elbow_joint" instance="elbow_joint_position_controller"/>

<plugin name="ur5e_wrist_1" joint="ur5e_wrist_1_joint" instance="wrist_1_joint_position_controller"/>

<plugin name="ur5e_wrist_2" joint="ur5e_wrist_2_joint" instance="wrist_2_joint_position_controller"/>

<plugin name="ur5e_wrist_3" joint="ur5e_wrist_3_joint" instance="wrist_3_joint_position_controller"/>

</actuator>

  

<keyframe>

<key name="home" qpos="-1.5708 -1.5708 1.5708 -1.5708 -1.5708 0" ctrl="-1.5708 -1.5708 1.5708 -1.5708 -1.5708 0"/>

</keyframe>

</mujoco>
```

Expected behavior The expected behavior would ideally being able to run my simulation with both keyframes and the PID controllers. If there are alternative solutions or I am somehow misusing the tools within MuJoCo please let me know.

Error Messages As mentioned previously the error message when loading in the scene as shown below mj.MjModel.from_xml_path(filename=self._scene_path) Is simply a Segmentation fault (core dumped) Desktop (please complete the following information):

  • OS: Ubuntu 20.04
  • Python Version 3.9.5
  • Mujoco Version 3.1.2
  • Python virtual environment

Any and all help, information, solutions to this or an alternative solution is very much appreciated, thanks in advance.

vmstavens avatar Feb 28 '24 14:02 vmstavens