google-deepmind / mujoco

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

Unity Integration Issue with MuJoCo 6-DOF Arm Robot and Gripper Simulation #1052

Closed brownbrowny closed 11 months ago

brownbrowny commented 11 months ago

Hi,

I'm a student and I'm trying to use MuJoCo for physics simulation in Unity with an 6 dof arm robot (later I want to use MLAgents for applying Reinforcement Learning for a pick & place task). Therefore I converted the URDF of to XML using drag and drop with the MuJoCo Simulator. I used the examples from the mujoco_menagerie to edit the generated XMLfile and fill in missing properties. I also added a gripper. Now when loading the model into the MujoCo Simulator, the gripper works as desired but when loading the same xml file into Unity it produces weird behaviour. I never used MuJoCo before and the documentation wasn't helpful for solving the issue.

Here is a model which explains my question:

<mujoco model="igus_rebel_6dof">
  <compiler angle="radian" meshdir="assets" autolimits="true"/>

  <default>
    <default class="igus_rebel_6dof">
      <material specular="0.5" shininess="0.25"/>
      <!-- <joint axis="0 1 0"/> -->
      <general gaintype="fixed" biastype="affine" gainprm="200" biasprm="0 -200 -40" forcerange="-330 330"/>
      <!-- <general gaintype="fixed" biastype="affine" gainprm="2000" biasprm="0 -2000 -400" forcerange="-330 330"/> -->
      <!-- <general dyntype="none" biastype="affine" forcerange="-330 330"/> -->
      <joint armature="0.1" damping="1" axis="0 0 1"/>
      <default class="joint1_class">
        <joint range="-3.12414 3.12414"/>
        <general ctrlrange="-3.12414 3.12414"/>
      </default>
      <default class="joint2_class">
        <joint range="-1.91986 1.91986"/>
        <general ctrlrange="-1.91986 1.91986"/>
      </default>
      <default class="joint3_class">
        <joint range="-1.52716 1.78896"/>
        <general ctrlrange="-1.52716 1.78896"/>
      </default>
      <default class="finger_joint">
        <joint axis="0 1 0" type="slide" range="0 0.01"/>
      </default>
      <default class="visual">
        <geom type="mesh" contype="0" conaffinity="0" group="2" material="light_gray"/>
      </default>
      <default class="collision">
        <geom type="mesh" group="3" material="orange"/>
      </default>
      <site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
    </default>
  </default>

  <asset>
    <material class="igus_rebel_6dof" name="light_gray" rgba="0.6 0.6 0.6 1"/>
    <material class="igus_rebel_6dof" name="orange" rgba="1 0.423529 0.0392157 1"/>

    ...

  </asset>

  <worldbody>
    <body name="base_link" childclass="igus_rebel_6dof">
      <inertial mass="1.0" pos="0 0 0" diaginertia="1 1 1"/>
      <geom class="visual" density="0" mesh="Joint0"/>
      <geom class="collision" mesh="Joint0Coll"/>
    <body name="link_1" pos="0 0 0.100001"> <!-- Bug occured when converting from xml to MuJoCo-Model collision between first and second link which disables movement of the joint -> small offset inserted  -->
      <inertial pos="0 0 0" mass="0.1" diaginertia="0.03 0.03 0.03"/>
      <joint class="joint1_class" name="joint1" pos="0 0 0" axis="0 0 -1"/>
      <geom class="visual" density="0" mesh="Joint1"/>
      <geom class="collision" mesh="Joint1Coll"/>
      <body name="link_2" pos="0 0 0.149" quat="0.965926 0 0.258819 0">
        <inertial pos="0 0 0" mass="0.1" diaginertia="0.03 0.03 0.03"/>
        <joint class="joint2_class" name="joint2" pos="0 0 0" axis="0 1 0"/>
        <geom class="visual" density="0" mesh="Joint2"/>
        <geom class="collision" mesh="Joint2Coll"/>
        <body name="link_5" pos="0 0 0.2384" quat="0.965926 0 0.258819 0">
          <inertial pos="0 0 0" mass="0.1" diaginertia="0.03 0.03 0.03"/>
          <joint class="joint2_class" name="joint3" pos="0 0 0" axis="0 1 0"/>
          <geom class="visual" density="0" mesh="Joint3"/>
          <geom class="collision" mesh="Joint3Coll"/>
          <body name="link_6" pos="0 0 0.119">
            <inertial pos="0 0 0" mass="0.1" diaginertia="0.03 0.03 0.03"/>
            <joint class="joint1_class" name="joint4" pos="0 0 0" axis="0 0 1"/>
            <geom class="visual" density="0" mesh="Joint4"/>
            <geom class="collision" mesh="Joint4Coll"/>
            <body name="link_7" pos="0 0 0.17" quat="0.997859 0 -0.0654031 0">
              <inertial pos="0 0 0" mass="0.1" diaginertia="0.03 0.03 0.03"/>
              <joint class="joint3_class" name="joint5" pos="0 0 0" axis="0 1 0"/>
              <geom class="visual" density="0" mesh="Joint5"/>
              <geom class="collision" mesh="Joint5Coll"/>
              <body name="link_8" pos="0 0 0.1208">
                <inertial pos="0 0 0.0006" mass="0.2" diaginertia="0.0600001 0.0600001 0.06"/>
                <joint class="joint1_class" name="joint6" pos="0 0 0" axis="0 0 1"/>
                <geom class="visual" density="0" mesh="Joint6"/>
                <geom class="collision" mesh="Joint6Coll"/>
                <body name="gripper" pos="0 0 0.001">
                  <inertial pos="0 0 0.0" mass="0.1" diaginertia="0.03 0.03 0.03"/>
                  <geom class="visual" density="0" mesh="gripper_base"/>
                  <body name="left_finger" pos="0 -0.027 0.1225">
                    <inertial mass="0.015" pos="0 0 0" diaginertia="2.375e-6 2.375e-6 7.5e-7"/>
                    <joint name="left_finger_joint" class="finger_joint"/>
                    <geom mesh="left_finger" class="visual"/>
                  </body>
                  <body name="right_finger" pos="0 0.027 0.1225" quat="0 0 0 1">
                    <inertial mass="0.015" pos="0 0 0" diaginertia="2.375e-6 2.375e-6 7.5e-7"/>
                    <joint name="right_finger_joint" class="finger_joint"/>
                    <geom mesh="right_finger" class="visual"/>
                  </body>
                </body>
              </body>
            </body>
          </body>
        </body>
      </body>
    </body>
  </body>
  </worldbody>

  <tendon>
    <fixed name="split">
      <joint joint="left_finger_joint" coef="0.5"/>
      <joint joint="right_finger_joint" coef="0.5"/>
    </fixed>
  </tendon>

  <equality>
    <joint joint1="left_finger_joint" joint2="right_finger_joint" solimp="0.95 0.99 0.001" solref="0.005 1"/>
  </equality>

  <actuator>
    <general name="a1" joint="joint1" class="joint1_class"/>
    <general name="a2" joint="joint2" class="joint2_class"/>
    <general name="a3" joint="joint3" class="joint2_class"/>
    <general name="a4" joint="joint4" class="joint1_class"/>
    <general name="a5" joint="joint5" class="joint3_class"/>
    <general name="a6" joint="joint6" class="joint1_class"/>
    <general name="a7" tendon="split" forcerange="-100 100" ctrlrange="0 255" />
    <!-- copied from Emika Franka Robot but doesn't work because of gain and bias parameters <general name="a7" tendon="split" forcerange="-100 100" ctrlrange="0 255"gainprm="0.0039215686 0 0" biasprm="0 -100 -10"/> -->
  </actuator>

  <keyframe>
    <key name="home" qpos="0 -0.349 1.9198 0 1.5707 0 0.01 0.01" ctrl="1 -0.349 1.9198 0 1.5707 0 255"/>
  </keyframe>

</mujoco>

Here are two videos illustrating my question:

https://github.com/google-deepmind/mujoco/assets/53004795/522be704-b445-4904-8683-b8fab9a9e034

https://github.com/google-deepmind/mujoco/assets/53004795/ad841aac-5be4-4fd2-9e8b-c5e231acb889

Thanks already.

Balint-H commented 11 months ago

It looks like the autolimits were not imported correctly. Try setting the joint limits for the gripper manually in the Unity inspector (and also set the Limited property to true).

brownbrowny commented 11 months ago

I first assumed you meant the parameters Ctrl Limited or Force Limited within the Common Params-section of the actuator element which didn't make a difference. I then tried ticking the Limited option (within the Solver-Section) in the tendon element and that worked. Thanks. image