Couple questions regarding transfer URDF model to xml

Discussion in 'Modeling' started by Wei Ding, Feb 13, 2019.

  1. Hey folks,

    I have couple questions regarding converting URDF to XML.

    1. Box sizes
    I have a urdf,
    Code:
      <link name="body">
        <visual>
          <origin rpy="0 0 0" xyz="0 0 0"/>
          <geometry>
            <!-- <box size="0.88 0.25 0.19"/> -->
            <mesh scale="0.0009 0.0009 0.0009" filename="mesh/body_frame.STL"/>
          </geometry>
          <material name="gray"/>
        </visual>
        <inertial>
          <mass value="12"/>
          <!-- Uniform box -->
          <inertia ixx="0.058" ixy="0" ixz="0" iyy="0.149" iyz="0" izz="0.195"/>
        </inertial>
        <!-- Just copy geometry for collision -->
        <collision>
          <geometry>
            <box size="0.05 0.25 0.19"/>
          </geometry>
        </collision>
      </link>
    It gets translated to:
    Code:
    <body name="body" pos="0 0 0">
                <inertial pos="0 0 0" quat="0 0.707107 0 0.707107" mass="12" diaginertia="0.195 0.149 0.058" />
                <geom size="0.025 0.125 0.095" type="box" rgba="0.5 0.5 0.5 0.7" />
    I was wondering:
    Why the box size get translated from "0.05 0.25 0.19" to "0.025 0.125 0.095"? How does the conversion work? Besides this body, looks like all other body are also changed in size.

    2. Is motor inertia something I can set in the model?
    In urdf I can set transmission like:
    Code:
    <transmission name="hipRoll0Transmission">
        <joint name="hipRoll0"/>
        <actuator>
          <mechanicalReduction>186</mechanicalReduction>
          <motorInertia>0.00000768</motorInertia>
        </actuator>
    </transmission>
    In Mujoco xml, I can set motor gear ratio (I guess it's equivalent as mechanicalReduction), but is there a equivalent parameter for motorInertia?

    Thank you very much!
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    1. mujoco sizes have the meaning of radius, not diameter.

    2. in mujoco this is called "armature" and is a property of the joint, not the motor.
     
  3. Thank you very much professor Todorov! This is very helpful!

    I got one more question. I have a xml (call robot.xml) that has data like this:
    Code:
     <body name="hip0" pos="0.325 0.1575 0">
                    <inertial pos="0 0 0" mass="2.75" diaginertia="0.0058 0.0058 0.0027" />
                    <joint name="hipRoll0" pos="0 0 0" axis="1 0 0" limited="true" range="-0.43 0.43" />
                    <geom size="0.0975 0.05 0.085" pos="0 -0.039 0" quat="0.707107 0.707107 0 0" type="box" rgba="0.8 0 0.2 1" />
    Then I have another xml (call combined.xml) that adds floor and include the xml (robot.xml) as above. Then I compile the combined.xml, it gave me data like:
    Code:
    <body name="hip0" pos="0.325 0.1575 0">
    <inertial pos="0 -0.039 0" quat="0.707107 0.707107 0 0" mass="3.315" diaginertia="0.0107461 0.018488 0.0132669" />
    <joint name="hipRoll0" pos="0 0 0" axis="1 0 0" limited="true" range="-0.43 0.43" />
    <geom size="0.0975 0.05 0.085" pos="0 -0.039 0" quat="0.707107 0.707107 0 0" type="box" rgba="0.8 0 0.2 1" />
    
    I was wondering why would the mass change?
     
    Last edited: Feb 14, 2019