Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

what's the meanning of filter_ints about collision and how could we set appropriate value about filter_ints for self define robot type, #114

Open
dbdxnuliba opened this issue Dec 30, 2024 · 2 comments

Comments

@dbdxnuliba
Copy link

dbdxnuliba commented Dec 30, 2024

@ZhengyiLuo @kangnil @kexul @siyuzou ,Hello,
I try add

<joint armature="1e-2"/>

in xml,
image

but the episode_length is still too low
image

when train :
self_rob.yaml
set has_self_collision: True
aa1

when evaluation
and after 18000 iterations, when evaluate ,it shows as the following:

data1

So

Why is the joint movement of this agent not continuous during training? and why the trained result not work?Is it because of the collision settings in my XML or the corresponding filter_ints not being set correctly?
and self_rob.xml define

<mujoco model="self_rob">
  <compiler angle="radian" meshdir="meshes/" autolimits="true" discardvisual="false"/>
  <statistic meansize="0.144785" extent="1.23314" center="0.025392 2.0634e-05 -0.245975"/>
  <default>
    <joint armature="1e-2"/>
    <default class="visual">
      <geom contype="0" conaffinity="0" group="0" density="0"/>
    </default>
    <default class="collision">
      <geom group="1"/>
    </default>
  </default>
    <asset>
    <texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="512"/>
    <texture name="texplane" type="2d" builtin="checker" rgb1=".2 .3 .4" rgb2=".1 0.15 0.2"
        width="512" height="512" mark="cross" markrgb=".8 .8 .8"/>
    <texture name="texplane2" type="2d" builtin="checker" rgb1="1 0.3137 0.1843" rgb2="0.0 0.30196 0.38039"
        width="512" height="512" mark="cross" markrgb=".8 .8 .8"/>

    <material name="matplane" reflectance="0." texture="texplane" texrepeat="1 1" texuniform="true"/>
    <material name="matplane2" reflectance="0.1" texture="texplane2" texrepeat="1 1" texuniform="true"/>

    <material name='obstacle'  rgba='0.9 0.6 0.2 1'/>
    <material name='visualgeom'  rgba='0.5 0.9 0.2 1'/>
    <material name='visualgeom2'  rgba='0.5 0.9 0.2 1'/>
    <mesh name="base_link" file="base_link.STL"/>
    <mesh name="base_link_smf" file="base_link_smf.STL"/>
    <mesh name="neck_yaw_link" file="neck_yaw_link.STL"/>
    <mesh name="neck_pitch_link" file="neck_pitch_link.STL"/>
    <mesh name="mic_link" file="mic_link.STL"/>
    <mesh name="head_rs_link" file="head_rs_link.STL"/>
    <mesh name="left_arm_base_link" file="left_arm_base_link.STL"/>
    <mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
    <mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
    <mesh name="left_arm_yaw_link" file="left_arm_yaw_link.STL"/>
    <mesh name="left_elbow_pitch_link" file="left_elbow_pitch_link.STL"/>
    <mesh name="left_elbow_yaw_link" file="left_elbow_yaw_link.STL"/>
    <mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
    <mesh name="left_wrist_pitch_link_smf" file="left_wrist_pitch_link_smf.STL"/>

    
    <mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
    <mesh name="left_hand_base_link" file="left_hand_base_link.STL"/>
    <mesh name="left_hand_ee_link" file="left_hand_ee_link.STL"/>
    <mesh name="right_arm_base_link" file="right_arm_base_link.STL"/>
    <mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
    <mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
    <mesh name="right_arm_yaw_link" file="right_arm_yaw_link.STL"/>
    <mesh name="right_elbow_pitch_link" file="right_elbow_pitch_link.STL"/>
    <mesh name="right_elbow_yaw_link" file="right_elbow_yaw_link.STL"/>
    <mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
    <mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
    <mesh name="right_hand_base_link" file="right_hand_base_link.STL"/>
    <mesh name="right_hand_ee_link" file="right_hand_ee_link.STL"/>
    <mesh name="waist_base_link" file="waist_base_link.STL"/>
    <mesh name="waist_pitch_link" file="waist_pitch_link.STL"/>
    <mesh name="waist_roll_link" file="waist_roll_link.STL"/>
    <mesh name="waist_roll_link_smf" file="waist_roll_link_smf.STL"/>

    <mesh name="waist_yaw_link" file="waist_yaw_link.STL"/>
    <mesh name="waist_yaw_link_smf" file="waist_yaw_link_smf.STL"/>

    <mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
    <mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
    <mesh name="left_hip_yaw_link_smf" file="left_hip_yaw_link_smf.STL"/>
    <mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
    <mesh name="left_knee_link" file="left_knee_link.STL"/>
    <mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
    <mesh name="left_ankle_pitch_link_smf" file="left_ankle_pitch_link_smf.STL"/>


    <mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
    <mesh name="left_ankle_roll_link_smf" file="left_ankle_roll_link_smf.STL"/>


    
    <mesh name="left_foot_ee_link" file="left_foot_ee_link.STL"/>
    <!-- <mesh name="left_ankle_pitch_motor_link" file="left_ankle_pitch_motor_link.STL"/>
    <mesh name="left_ankle_pitch_linkage_link" file="left_ankle_pitch_linkage_link.STL"/>
    <mesh name="left_ankle_roll_motor_link" file="left_ankle_roll_motor_link.STL"/>
    <mesh name="left_ankle_roll_linkage_link" file="left_ankle_roll_linkage_link.STL"/>
    <mesh name="left_knee_motor_link" file="left_knee_motor_link.STL"/> -->
    <!-- <mesh name="left_knee_linkage_link" file="left_knee_linkage_link.STL"/> -->
    <mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
    <mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
    <mesh name="right_hip_yaw_link_smf" file="right_hip_yaw_link_smf.STL"/>

    <mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
    <mesh name="right_knee_link" file="right_knee_link.STL"/>
    <mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
    <mesh name="right_ankle_pitch_link_smf" file="right_ankle_pitch_link_smf.STL"/>

    
    <mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
    <mesh name="right_ankle_roll_link_smf" file="right_ankle_roll_link_smf.STL"/>

    
    <mesh name="right_foot_ee_link" file="right_foot_ee_link.STL"/>
    <mesh name="base_rs_link" file="base_rs_link.STL"/>
  
    <hfield name='hf0' nrow='200' ncol='200' size="10 5 0.2 .1"/>
  </asset>
  <worldbody>
    <light directional="true" diffuse=".4 .4 .4" specular="0.1 0.1 0.1" pos="0 0 5.0" dir="0 0 -1" castshadow="false"/>
    <light directional="true" diffuse=".6 .6 .6" specular="0.2 0.2 0.2" pos="0 0 4" dir="0 0 -1"/>
    <geom name="ground" type="plane" size="0 0 1" pos="0.001 0 0" quat="1 0 0 0" material="matplane" condim="1" conaffinity='15'/>

    <body name="waist_yaw_link" pos="0 0 1.0">
      <inertial pos="-0.064098 -0.00018359 -0.074077" mass="5.39"  diaginertia="0.068 0.0188 0.0756" />
      <joint name="floating_joint" type="free" />
      <!-- <joint type='slide' axis='1 0 0' limited='false' />
      <joint type='slide' axis='0 1 0' limited='false' />
      <joint type='slide' axis='0 0 1' limited='false' /> -->
      <!-- <joint type='ball' limited='false' /> -->

      <!-- <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 1 1 1"
        mesh="waist_yaw_link" class="visualgeom"/>      -->
        <!-- <geom type="mesh" class="visual" rgba="0.2 0.2 0.2 1" mesh="waist_yaw_link"/>
        <geom type="mesh" class="collision" rgba="0.2 0.2 0.2 1" mesh="waist_yaw_link"/>         -->

        <geom type="mesh" class="visual" rgba="0.75294 0.75294 0.75294 1" mesh="waist_yaw_link_smf"/>
        <geom type="mesh" class="collision" rgba="0.75294 0.75294 0.75294 1" mesh="waist_yaw_link_smf"/>    


    <body name="left_hip_roll_link" pos="0 0.115 -0.079">
      <inertial pos="-0.0016523 6.6007e-06 0.003973" quat="-0.000474014 0.717758 -0.000328028 0.696292" mass="1.6446" diaginertia="0.00294309 0.0024 0.00229941"/>
      <joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.21 1.22" />

      <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_hip_roll_link" class="visual"/>
      <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_hip_roll_link" class="collision"/> -->
      <geom size="0.05 0.035" pos="0 0 0.01" type="cylinder" rgba="0.75294 0.75294 0.75294 1" class="visual"/>
      <geom size="0.05 0.035" pos="0 0 0.01" type="cylinder" rgba="0.75294 0.75294 0.75294 1" class="collision"/>

      <body name="left_hip_yaw_link">
        <inertial pos="-0.00030509 -0.036415 -0.13923" quat="0.713473 0.0192164 -0.0375138 0.699413" mass="3.9286" diaginertia="0.0163503 0.0107994 0.00885028"/>
        <joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-0.52 1.22" />
        <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_hip_yaw_link" class="visual"/>
        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_hip_yaw_link" class="collision"/> -->
        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_hip_yaw_link_smf" class="visual"/>
        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_hip_yaw_link_smf" class="collision"/>


        <body name="left_hip_pitch_link" pos="0 -0.01 -0.144" quat="0.965926 0 -0.25882 0">
          <inertial pos="0.0017618 0.037227 -0.029964" quat="0.486855 0.0575918 -0.0505226 0.870117" mass="4.6841" diaginertia="0.0434235 0.0418811 0.00459533"/>
          <joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.57 1.4" />
          <!-- <geom type="mesh" rgba="1 1 1 1" mesh="left_hip_pitch_link" class="visualgeom"/> -->
          <geom type="mesh" rgba="1 1 1 1" mesh="left_hip_pitch_link" class="visual"/>
          <geom type="mesh" rgba="1 1 1 1" mesh="left_hip_pitch_link" class="collision"/>

          <body name="left_knee_link" pos="0 0 -0.36" quat="0.866025 0 0.500001 0">
            <inertial pos="0.019103 -4.8925e-06 -0.11971" quat="0.996818 0.0018809 -0.0157021 0.0781216" mass="2.1362" diaginertia="0.0180159 0.0180002 0.00188387"/>
            <joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-1.1 1.31" />
            <!-- <geom type="mesh" rgba="1 1 1 1" mesh="left_knee_link" class="visualgeom"/> -->
            <geom type="mesh" rgba="1 1 1 1" mesh="left_knee_link" class="visual"/>
            <geom type="mesh" rgba="1 1 1 1" mesh="left_knee_link" class="collision"/>

            <body name="left_ankle_pitch_link" pos="0 0 -0.36" quat="0.965926 0 -0.25882 0">
              <inertial pos="-0.00077711 1.5934e-09 5.1139e-05" quat="2.59788e-06 0.706535 2.59369e-06 0.707678" mass="0.080248" diaginertia="6.4137e-06 5.5064e-06 4.8112e-06"/>
              <joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.66 1.22" />
              <geom type="mesh" rgba="1 1 1 1" mesh="left_ankle_pitch_link" class="visual"/>
              <geom type="mesh" rgba="1 1 1 1" mesh="left_ankle_pitch_link" class="collision"/>

              <!-- <body name="left_ankle_roll_link">
                <inertial pos="0.035309 -1.4216e-06 -0.045803" quat="-2.50196e-05 0.677318 -4.47533e-05 0.73569" mass="0.85281" diaginertia="0.00422483 0.004 0.000575171"/>
                <joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.31 0.31" />
                <geom type="mesh" rgba="1 1 1 1" mesh="left_ankle_roll_link" class="visual" />
                <geom type="mesh" rgba="1 1 1 1" mesh="left_ankle_roll_link"  class="collision"/>
              </body> -->
              <body name="left_ankle_roll_link">
                <inertial pos="0.035309 -1.4216e-06 -0.045803" quat="-2.50196e-05 0.677318 -4.47533e-05 0.73569" mass="0.85281" diaginertia="0.00422483 0.004 0.000575171"/>
                <joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.31 0.31"/>
                <geom type="mesh" rgba="1 1 1 1" mesh="left_ankle_roll_link_smf" class="visual"/>
                <geom type="mesh" rgba="1 1 1 1" mesh="left_ankle_roll_link_smf" class="collision"/>
              </body>

            </body>
          </body>
        </body>
      </body>
    </body>
    <body name="right_hip_roll_link" pos="0 -0.115 -0.079">
      <inertial pos="-0.0016523 6.6007e-06 0.003973" quat="-0.000399321 0.715678 -0.000222781 0.69843" mass="1.6446" diaginertia="0.00310048 0.0024 0.00229952"/>
      <joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.22 0.21" />
      <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_hip_roll_link"  class="visual"/>
      <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_hip_roll_link"  class="collision" /> -->
      <geom size="0.05 0.035" pos="0 0 0.01" type="cylinder" rgba="0.75294 0.75294 0.75294 1" class="visual"/>
      <geom size="0.05 0.035" pos="0 0 0.01" type="cylinder" rgba="0.75294 0.75294 0.75294 1" class="collision"/>
      <body name="right_hip_yaw_link">
        <inertial pos="-0.00055103 0.036441 -0.13872" quat="0.700231 -0.028796 0.0364519 0.712403" mass="3.9259" diaginertia="0.0163665 0.0107985 0.00873502"/>
        <joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.22 0.52" />
        <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_hip_yaw_link" class="visual"/>
        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_hip_yaw_link" class="collision"/> -->

        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_hip_yaw_link_smf" class="visual"/>
        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_hip_yaw_link_smf" class="collision"/>

        <body name="right_hip_pitch_link" pos="0 0.01 -0.144" quat="0.965926 0 -0.25882 0">
          <inertial pos="0.001563 -0.037227 -0.029942" quat="0.845667 -0.0573307 0.0722459 0.525682" mass="4.6841" diaginertia="0.0434386 0.042055 0.0110065"/>
          <joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.57 1.4" />
          <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_hip_pitch_link" class="visualgeom"/> -->
          <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_hip_pitch_link" class="visual"/>
          <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_hip_pitch_link" class="collision"/>

          <body name="right_knee_link" pos="0 0 -0.36" quat="0.866025 0 0.500001 0">
            <inertial pos="0.01895 -4.8931e-06 -0.11968" quat="0.699755 -0.0130729 -0.00854403 0.714212" mass="2.1362" diaginertia="0.0183006 0.0182153 0.00188407"/>
            <joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-1.1 1.31" />
            <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_knee_link" class="visualgeom"/> -->
            <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_knee_link" class="visual"/>
            <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_knee_link" class="collision"/>

            <body name="right_ankle_pitch_link" pos="0 0 -0.36" quat="0.965926 0 -0.25882 0">
              <inertial pos="0.00077711 1.5954e-09 -5.1139e-05" quat="-2.59192e-06 0.706535 -2.58773e-06 0.707678" mass="0.080248" diaginertia="6.4137e-06 5.5064e-06 4.8112e-06"/>
              <joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.66 1.22" />
              <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_ankle_pitch_link" class="visualgeom"/> -->
              <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_ankle_pitch_link" class="visual"/>
              <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_ankle_pitch_link" class="collision"/>

              <!-- <body name="right_ankle_roll_link">
                <inertial pos="0.03731 -1.4676e-06 -0.045803" quat="-2.64594e-05 0.677318 -4.71403e-05 0.73569" mass="0.85281" diaginertia="0.00422483 0.004 0.000575171"/>
                <joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.31 0.31" />
                <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_ankle_roll_link" class="visual"/>
                <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_ankle_roll_link" class="collision"/>
              </body> -->

              <body name="right_ankle_roll_link">
                <inertial pos="0.03731 -1.4676e-06 -0.045803" quat="-2.64594e-05 0.677318 -4.71403e-05 0.73569" mass="0.85281" diaginertia="0.00422483 0.004 0.000575171"/>
                <joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.31 0.31"/>
                <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_ankle_roll_link_smf" class="visual"/>
                <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_ankle_roll_link_smf" class="collision"/>
              </body>
            </body>
          </body>
        </body>
      </body>
    </body>
    <body name="waist_roll_link">
      <inertial pos="0.0028204 2.6985e-09 -0.017965" quat="5.71086e-05 0.92388 5.76654e-05 0.382683" mass="0.15785" diaginertia="0.000101199 0.0001 9.88008e-05"/>
      <joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.57 1.57" />
      <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="waist_roll_link" class="visual"/>
      <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="waist_roll_link" class="collision"/> -->
      <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="waist_roll_link_smf" class="visual"/>
      <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="waist_roll_link_smf" class="collision"/> -->
      <geom size="0.01 0.01 0.002" pos="0 0 -0.015" type="box" rgba="0.75294 0.75294 0.75294 1" class="visual"/>
      <geom size="0.01 0.01 0.002" pos="0 0 -0.015" type="box" rgba="0.75294 0.75294 0.75294 1" class="collision"/>



      <body name="waist_pitch_link">
        <inertial pos="-3.9493e-09 -5.5675e-09 -5.9673e-05" quat="0 0.707107 0 0.707107" mass="0.068747" diaginertia="8.9493e-06 5.5342e-06 5.3442e-06"/>
        <joint name="waist_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.26 0.26" />
        <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="waist_pitch_link" class="visualgeom"/> -->
        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="waist_pitch_link" class="visual"/>
        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="waist_pitch_link" class="collision"/>

        <body name="waist_tmp_link">
          <inertial pos="0.00889035 0.00164106 0.0586304" quat="0.999742 0.00259905 0.00447905 0.0221029" mass="15.7244" diaginertia="0.945253 0.887166 0.139739"/>
          <joint name="waist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.05 0.09" />
          <!-- <geom pos="0 0 0.1015" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="base_link" class="visualgeom"/>
          <geom pos="0 0 0.338" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="neck_yaw_link" class="visualgeom"/>
          <geom pos="0.032 0 0.4915" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="neck_pitch_link" class="visualgeom"/> -->

          <!-- <geom pos="0 0 0.1015" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="base_link" class="visual"/>
          <geom pos="0 0 0.1015" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="base_link" class="collision"/> -->
          <geom pos="0 0 0.1015" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="base_link_smf" class="visual"/>
          <geom pos="0 0 0.1015" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="base_link_smf" class="collision"/>

          <geom pos="0 0 0.338" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="neck_yaw_link" class="visual"/>
          <geom pos="0.032 0 0.4915" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="neck_pitch_link" class="visual"/>
          <!-- <geom pos="0.032 0 0.4915" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="neck_pitch_link" class="collision"/> -->

          <!-- <geom pos="0 0.112 0.338" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_arm_base_link"/>
          <geom pos="0 -0.112 0.338" type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_arm_base_link"/> -->
          <body name="left_shoulder_pitch_link" pos="0 0.112 0.338">
            <inertial pos="-0.010548 0.12346 -0.021666" quat="0.552208 0.765286 -0.307754 0.121208" mass="1.1618" diaginertia="0.00204334 0.00196649 0.00140478"/>
            <joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.79 2.79" />
            <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_shoulder_pitch_link" class="visualgeom"/> -->
            <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_shoulder_pitch_link" class="visual"/>
            <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_shoulder_pitch_link" class="collision"/>

            <body name="left_shoulder_roll_link" pos="0 0.133 -0.025">
              <inertial pos="-0.0010652 -0.00016594 -0.091811" quat="0.384447 0.00429405 -0.00256563 0.923134" mass="1.1852" diaginertia="0.00290254 0.00289759 0.00159987"/>
              <joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.24 1.83" />
              <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_shoulder_roll_link" class="visualgeom"/> -->
              <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_shoulder_roll_link" class="visual"/>
              <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_shoulder_roll_link" class="collision"/>
              <body name="left_arm_yaw_link">
                <inertial pos="0.0033229 -0.0016876 -0.18801" quat="0.98894 0.00121636 -0.148284 0.00274462" mass="0.354" diaginertia="0.00114156 0.001 0.00065844"/>
                <joint name="left_arm_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.79 2.79" />
                <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_arm_yaw_link" class="visualgeom"/> -->
                <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_arm_yaw_link" class="visual"/>
                <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_arm_yaw_link" class="collision"/>
                <body name="left_elbow_pitch_link" pos="0.016 0 -0.232">
                  <inertial pos="-0.0079717 -0.0068363 -0.045353" quat="0.977995 0.0762126 -0.07713 -0.178238" mass="1.567" diaginertia="0.00491925 0.00483994 0.00144081"/>
                  <joint name="left_elbow_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.36 0.79" />
                  <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_elbow_pitch_link" class="visualgeom"/> -->
                  <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_elbow_pitch_link" class="visual"/>
                  <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_elbow_pitch_link" class="collision"/>
                  <body name="left_elbow_yaw_link" pos="-0.016 0 -0.166">
                    <inertial pos="3.0416e-06 -0.001965 0.030234" quat="0.493934 0.504724 -0.505716 0.495514" mass="0.1556" diaginertia="0.000200044 0.00019055 9.99559e-05"/>
                    <joint name="left_elbow_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.62 2.62" />
                    <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_elbow_yaw_link" class="visualgeom"/> -->
                    <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_elbow_yaw_link" class="visual"/>
                    <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_elbow_yaw_link" class="collision"/>
                    <body name="left_wrist_pitch_link">
                      <inertial pos="-0.00027663 -0.0069214 -0.0061943" quat="0.680163 0.0138059 -0.0115802 0.732839" mass="0.625" diaginertia="0.000600258 0.000600003 0.00039974"/>
                      <joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.57 1.57" />
                      <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_wrist_pitch_link" class="visualgeom"/> -->
                      <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_wrist_pitch_link" class="visual"/>
                      <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_wrist_pitch_link" class="collision"/> -->
                      <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_wrist_pitch_link_smf" class="visual"/>
                      <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_wrist_pitch_link_smf" class="collision"/>

                      
                      <!-- <body name="left_wrist_roll_link" pos="0 0 -0.065">
                        <inertial pos="-0.0075938 0.00010133 -0.00064617" quat="0.67426 0.634496 -0.278211 0.25571" mass="0.58" diaginertia="0.000300524 0.000299562 0.000278783"/>
                        <joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.75 1.75" />
                        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_wrist_roll_link" class="visual"/>
                        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="left_wrist_roll_link" class="collision"/>                        
                      </body> -->

                      <body name="left_wrist_roll_link" pos="0 0 -0.065">
                        <inertial pos="-0.0075938 0.00010133 -0.00064617" quat="0.67426 0.634496 -0.278211 0.25571" mass="0.58" diaginertia="0.000300524 0.000299562 0.000278783"/>
                        <joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.75 1.75" frictionloss="1.111"/>
                        <geom size="0.025 0.025 0.015" pos="0 0 -0.03" type="box" rgba="0.75294 0.75294 0.75294 1" class="visual"/>
                        <geom size="0.025 0.025 0.015" pos="0 0 -0.03" type="box" rgba="0.75294 0.75294 0.75294 1" class="collision"/>

                      </body>
                    </body>
                  </body>
                </body>
              </body>
            </body>
          </body>
          <body name="right_shoulder_pitch_link" pos="0 -0.112 0.338">
            <inertial pos="-0.010534 -0.1231 -0.021409" quat="0.468396 0.547269 -0.528461 0.449257" mass="1.1634" diaginertia="0.00192105 0.00189997 0.00148928"/>
            <joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.79 2.79" />
            <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_shoulder_pitch_link" class="visualgeom"/> -->
            <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_shoulder_pitch_link" class="visual"/>
            <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_shoulder_pitch_link" class="collision"/>
            <body name="right_shoulder_roll_link" pos="0 -0.133 -0.025">
              <inertial pos="-0.001069 2.5863e-05 -0.09185" quat="0.385959 0.000931079 0.00557584 0.922499" mass="1.1852" diaginertia="0.00290261 0.00289755 0.00159983"/>
              <joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.83 0.24" />
              <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_shoulder_roll_link" class="visualgeom"/> -->
              <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_shoulder_roll_link" class="visual"/>
              <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_shoulder_roll_link" class="collision"/>
              <body name="right_arm_yaw_link">
                <inertial pos="0.0018254 0.0021888 -0.18116" quat="0.996471 -0.000808841 -0.0839173 -0.00137869" mass="0.35384" diaginertia="0.00111185 0.001 0.000688148"/>
                <joint name="right_arm_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.79 2.79" />
                <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_arm_yaw_link" class="visualgeom"/> -->
                <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_arm_yaw_link" class="visual"/>
                <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_arm_yaw_link" class="collision"/>
                <body name="right_elbow_pitch_link" pos="0.016 0 -0.232">
                  <inertial pos="-0.008079 0.0068364 -0.045351" quat="0.927849 0.0270285 -0.0884426 0.361308" mass="1.8745" diaginertia="0.005019 0.00470097 0.00148003"/>
                  <joint name="right_elbow_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.36 0.79" />
                  <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_elbow_pitch_link" class="visualgeom"/> -->
                  <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_elbow_pitch_link" class="visual"/>
                  <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_elbow_pitch_link" class="collision"/>
                  <body name="right_elbow_yaw_link" pos="-0.016 0 -0.166">
                    <inertial pos="-3.0641e-06 0.001965 0.030234" quat="0.505716 0.495514 -0.493934 0.504724" mass="0.1556" diaginertia="0.000200044 0.00019055 9.99559e-05"/>
                    <joint name="right_elbow_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.62 2.62" />
                    <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_elbow_yaw_link" class="visualgeom"/> -->
                    <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_elbow_yaw_link" class="visual"/>
                    <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_elbow_yaw_link" class="collision"/>
                    <body name="right_wrist_pitch_link">
                      <inertial pos="-0.00021408 0.007602 -0.0035533" quat="0.397194 0.00168472 0.00938023 0.917685" mass="0.625" diaginertia="0.00060026 0.000599813 0.000399927"/>
                      <joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.57 1.57" />
                      <!-- <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_wrist_pitch_link" class="visualgeom"/> -->
                      <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_wrist_pitch_link" class="visual"/>
                      <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_wrist_pitch_link" class="collision"/>
                      <!-- <body name="right_wrist_roll_link" pos="0 0 -0.065">
                        <inertial pos="-0.0075938 0.00010133 -0.00064617" quat="0.733276 0.679087 -0.0338376 -0.00128758" mass="0.584" diaginertia="0.000300076 0.000290041 0.000278753"/>
                        <joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.75 1.75" />
                        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_wrist_roll_link" class="visual"/>
                        <geom type="mesh" rgba="0.75294 0.75294 0.75294 1" mesh="right_wrist_roll_link" class="collision"/>
                      </body> -->
                      <body name="right_wrist_roll_link" pos="0 0 -0.065">
                        <inertial pos="-0.0075938 0.00010133 -0.00064617" quat="0.733276 0.679087 -0.0338376 -0.00128758" mass="0.584" diaginertia="0.000300076 0.000290041 0.000278753"/>
                        <joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.75 1.75" frictionloss="1.111"/>
                        <geom size="0.025 0.025 0.015" pos="0 0 -0.03" type="box" rgba="0.75294 0.75294 0.75294 1" class="visual"/>
                        <geom size="0.025 0.025 0.015" pos="0 0 -0.03" type="box" rgba="0.75294 0.75294 0.75294 1" class="collision"/>
                      </body>
                    </body>
                  </body>
                </body>
              </body>
            </body>
          </body>
        </body>
      </body>
    </body>
  </body>
  </worldbody>

  <actuator>
    <motor name="left_hip_roll_joint" joint="left_hip_roll_joint"  ctrllimited="true" ctrlrange="-240 240"/>
    <motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"  ctrllimited="true" ctrlrange="-95.888 95.888"/>
    <motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"  ctrllimited="true" ctrlrange="-360.99 360.99"/>
    <motor name="left_knee_joint" joint="left_knee_joint" ctrllimited="true" ctrlrange="-360.99 360.99"/>
    <motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"  ctrllimited="true" ctrlrange="-43.888 43.888"/>
    <motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"  ctrllimited="true" ctrlrange="-43.888 43.888"/>
    <motor name="right_hip_roll_joint" joint="right_hip_roll_joint" ctrllimited="true" ctrlrange="-240 240"/>
    <motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"  ctrllimited="true" ctrlrange="-95.888 95.888"/>
    <motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"  ctrllimited="true" ctrlrange="-360.99 360.99"/>
    <motor name="right_knee_joint" joint="right_knee_joint"  ctrllimited="true" ctrlrange="-360.99 360.99"/>
    <motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"  ctrllimited="true" ctrlrange="-43.888 43.888"/>
    <motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint" ctrllimited="true" ctrlrange="-43.888 43.888"/>
    <motor name="waist_yaw_joint" joint="waist_yaw_joint"  ctrllimited="true" ctrlrange="-100 100"/>
    <motor name="waist_roll_joint" joint="waist_roll_joint" ctrllimited="true" ctrlrange="-110 110"/>
    <motor name="waist_pitch_joint" joint="waist_pitch_joint"  ctrllimited="true" ctrlrange="-110 110"/>
    <motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"  ctrllimited="true" ctrlrange="-110 110"/>
    <motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint" ctrllimited="true" ctrlrange="-110 110"/>
    <motor name="left_arm_yaw_joint" joint="left_arm_yaw_joint" ctrllimited="true" ctrlrange="-110 110"/>
    <motor name="left_elbow_pitch_joint" joint="left_elbow_pitch_joint" ctrllimited="true" ctrlrange="-110 110"/>
    <motor name="left_elbow_yaw_joint" joint="left_elbow_yaw_joint"  ctrllimited="true" ctrlrange="-35 35"/>
    <motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint" ctrllimited="true" ctrlrange="-35 35"/>
    <motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"  ctrllimited="true" ctrlrange="-35 35"/>
    <motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"  ctrllimited="true" ctrlrange="-110 110"/>
    <motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint" ctrllimited="true" ctrlrange="-110 110"/>
    <motor name="right_arm_yaw_joint" joint="right_arm_yaw_joint" ctrllimited="true" ctrlrange="-110 110"/>
    <motor name="right_elbow_pitch_joint" joint="right_elbow_pitch_joint"  ctrllimited="true" ctrlrange="-35 35"/>
    <motor name="right_elbow_yaw_joint" joint="right_elbow_yaw_joint" ctrllimited="true" ctrlrange="-35 35"/>
    <motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint" ctrllimited="true" ctrlrange="-35 35"/>
    <motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint" ctrllimited="true" ctrlrange="-35 35"/>
  </actuator>

</mujoco>


and filter_ints related code in humanoid.py:


   if self.humanoid_type in ['h1', 'g1', 'l3',"smpl", "smplh", "smplx"] and self._has_self_collision:
            # compliance_vals = [0.1] * 24
            # thickness_vals = [1.0] * 24
            if self._has_mesh:
                filter_ints = [0, 1, 224, 512, 384, 1, 1792, 64, 1056, 4096, 6, 6168, 0, 2048, 0, 20, 0, 0, 0, 0, 10, 0, 0, 0]
            else:
                if self.humanoid_type == "smpl":
                    filter_ints = [0, 0, 7, 16, 12, 0, 56, 2, 33, 128, 0, 192, 0, 64, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
                elif self.humanoid_type in ["smplh", "smplx"]:
                    filter_ints = [0, 0, 7, 16, 12, 0, 56, 2, 33, 128, 0, 192, 0, 64, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
                elif self.humanoid_type in ['h1']:
                    filter_ints = [0, 2, 0, 2, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
              
                elif self.humanoid_type in ['g1']:
                    filter_ints = [0, 0, 2688, 0, 8192, 0, 8192, 0, 1344, 0, 4096, 0, 4096, 3072, 768, 192, 1, 0, 1, 0, 32, 8, 40, 0, 0, 0, 0, 0, 2, 0, 2, 0, 16, 4, 20, 0, 0, 0, 0, 0]
                            
                elif self.humanoid_type in ['self_rob']:
                    filter_ints = [0,
                                    300, 2688, 300, 8192, 0, 8192,
                                    1, 1344, 1, 4096, 0, 4096, 
                                    3072, 4072, 0,
                                    0, 3, 0, 3, 0, 3, 0,
                                    0,2, 0, 2, 0, 2, 0]
                    
            props = self.gym.get_actor_rigid_shape_properties(env_ptr, humanoid_handle)
            print('len(filter_ints):', len(filter_ints))
            print('len(props):', len(props))
            assert (len(filter_ints) == len(props))


Could you please provide some advices,many thanks!

@HonglinChu
Copy link

I have the same question about “filter_int” setting for myself robot

@ZhengyiLuo
Copy link
Owner

The filter_int is set based on the self-collision API from IsaacGym. IsaacGym does not read the collision setting from XML so I have to set them manually. It's a bit-wise binary setting where if a body part has the same bit set to 1, they no longer collide.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants