leggedrobotics / raisimLib

RAISIM, A PHYSICS ENGINE FOR ROBOTICS AND AI RESEARCH
http://www.raisim.com
327 stars 50 forks source link

Robot from SolidWorks-sourced URDF falling through floor #52

Closed dyspr0sium closed 4 years ago

dyspr0sium commented 4 years ago

I am writing a Gym environment for a robot in Python using raisimpy, following the ANYmal example environment from raisimpy's examples. The ANYmal URDF loads in fine but using a URDF exported from SolidWorks, I cannot see the robot on the floor. With the floor not loaded visually in raisimOgre, I can see the robot falling down to infinity. I suspect there is a problem with the collision properties in the URDF, which are linked to OBJ files exported from SolidWorks rather than simple shapes defined directly in the URDF. The URDF is as follows:

<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) 
     Commit Version: 1.5.1-0-g916b5db  Build Version: 1.5.7152.31018
     For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
  name="Quadrupedal Robot URDF ready.SLDASM">
  <link
    name="Body">
    <inertial>
      <origin
        xyz="6.3895E-11 0.00012763 -0.017744"
        rpy="0 0 0" />
      <mass
        value="0.52729" />
      <inertia
        ixx="0.0019565"
        ixy="-6.0032E-10"
        ixz="1.2826E-08"
        iyy="0.00076333"
        iyz="-4.6881E-06"
        izz="0.0025305" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/Body.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.75294 0.75294 0.75294 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/Body.stl.obj" />
      </geometry>
    </collision>
  </link>
  <link
    name="L11">
    <inertial>
      <origin
        xyz="0.0243995568220635 -0.0139117596798611 -0.0357904787858385"
        rpy="0 0 0" />
      <mass
        value="0.0542977426736306" />
      <inertia
        ixx="1.67959891588832E-05"
        ixy="3.99700363772074E-07"
        ixz="4.4933479303535E-07"
        iyy="2.2247186909432E-05"
        iyz="-1.73903214218687E-06"
        izz="1.69288569652552E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L11.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L11.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="S1"
    type="revolute">
    <origin
      xyz="-0.0594999999999999 0.0539983931640023 -0.019"
      rpy="3.14159265358979 0 1.5707963267949" />
    <parent
      link="Body" />
    <child
      link="L11" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-2.1"
      upper="0.3"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L12">
    <inertial>
      <origin
        xyz="-0.0152238321171441 -2.25300842468523E-06 0.0464772913413802"
        rpy="0 0 0" />
      <mass
        value="0.0535927277366091" />
      <inertia
        ixx="2.51586892302995E-05"
        ixy="5.67635781226383E-10"
        ixz="-1.10421470951951E-06"
        iyy="2.95873597072862E-05"
        iyz="-4.43147241892655E-10"
        izz="1.0482568280809E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L12.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L12.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="E1"
    type="revolute">
    <origin
      xyz="0.0115016068359978 0 -0.04199999999999"
      rpy="-2.35619449019235 0 1.5707963267949" />
    <parent
      link="L11" />
    <child
      link="L12" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-1.1"
      upper="1.45"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L13">
    <inertial>
      <origin
        xyz="0.0155767383703316 0.00786484112620819 0.0325185046224157"
        rpy="0 0 0" />
      <mass
        value="0.021869144598202" />
      <inertia
        ixx="1.57449240659093E-05"
        ixy="1.85218206933391E-07"
        ixz="7.65678666734147E-07"
        iyy="1.89273636704953E-05"
        iyz="9.58350118217958E-07"
        izz="6.56779962831476E-06" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L13.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L13.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="K1"
    type="revolute">
    <origin
      xyz="0 0 0.0675"
      rpy="1.5707963267949 0 3.14159265358979" />
    <parent
      link="L12" />
    <child
      link="L13" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-3.2"
      upper="0.5"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L14">
    <inertial>
      <origin
        xyz="-0.003891 0.089782 -1.6556E-08"
        rpy="0 0 0" />
      <mass
        value="0.0048702" />
      <inertia
        ixx="4.7823E-07"
        ixy="-1.5635E-07"
        ixz="-4.7733E-13"
        iyy="3.2701E-07"
        iyz="-3.6521E-13"
        izz="6.9731E-07" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L14.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.79216 0.81961 0.93333 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L14.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="Foot1"
    type="fixed">
    <origin
      xyz="0.0145 0.0145 0.02554"
      rpy="1.5708 0 1.5708" />
    <parent
      link="L13" />
    <child
      link="L14" />
    <axis
      xyz="0 0 1" />
  </joint>
  <link
    name="L21">
    <inertial>
      <origin
        xyz="-0.0260020500139342 -0.0139117596798611 -0.0357904787858385"
        rpy="0 0 0" />
      <mass
        value="0.0542977426736306" />
      <inertia
        ixx="1.67959891588832E-05"
        ixy="3.99700363772073E-07"
        ixz="4.49334793035359E-07"
        iyy="2.2247186909432E-05"
        iyz="-1.73903214218687E-06"
        izz="1.69288569652552E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L21.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L21.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="S2"
    type="revolute">
    <origin
      xyz="-0.0595000000000008 -0.0556 -0.0190000000000003"
      rpy="3.14159265358979 0 1.5707963267949" />
    <parent
      link="Body" />
    <child
      link="L21" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-2.1"
      upper="0.3"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L22">
    <inertial>
      <origin
        xyz="-0.0152238321171441 -2.25300842466442E-06 0.0464772913413802"
        rpy="0 0 0" />
      <mass
        value="0.0535927277366092" />
      <inertia
        ixx="2.51586892302995E-05"
        ixy="5.67635781227972E-10"
        ixz="-1.1042147095195E-06"
        iyy="2.95873597072862E-05"
        iyz="-4.43147241911289E-10"
        izz="1.0482568280809E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L22.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L22.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="E2"
    type="revolute">
    <origin
      xyz="-0.0388999999999999 0 -0.04199999999999"
      rpy="-2.35619449019235 0 1.5707963267949" />
    <parent
      link="L21" />
    <child
      link="L22" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-1.1"
      upper="1.45"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L23">
    <inertial>
      <origin
        xyz="0.0155767383703317 0.007864841126208 0.0325185046224158"
        rpy="0 0 0" />
      <mass
        value="0.0218691445982019" />
      <inertia
        ixx="1.57449240659093E-05"
        ixy="1.85218206933387E-07"
        ixz="7.65678666734157E-07"
        iyy="1.89273636704953E-05"
        iyz="9.58350118217964E-07"
        izz="6.56779962831476E-06" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L23.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L23.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="K2"
    type="revolute">
    <origin
      xyz="0 0 0.0674999999999999"
      rpy="1.5707963267949 0 3.14159265358979" />
    <parent
      link="L22" />
    <child
      link="L23" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-3.2"
      upper="0.5"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L24">
    <inertial>
      <origin
        xyz="0.0072466 0.019677 0.0082129"
        rpy="0 0 0" />
      <mass
        value="0.0048702" />
      <inertia
        ixx="4.7823E-07"
        ixy="-1.5635E-07"
        ixz="-4.7733E-13"
        iyy="3.2701E-07"
        iyz="-3.6521E-13"
        izz="6.9731E-07" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L24.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.79216 0.81961 0.93333 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L24.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="Foot2"
    type="fixed">
    <origin
      xyz="0.0062871 0.0033624 0.095646"
      rpy="1.5708 0 1.5708" />
    <parent
      link="L23" />
    <child
      link="L24" />
    <axis
      xyz="0 0 1" />
  </joint>
  <link
    name="L31">
    <inertial>
      <origin
        xyz="-0.0243997055070884 -0.0139117596798611 -0.035793457414895"
        rpy="0 0 0" />
      <mass
        value="0.0542977426736307" />
      <inertia
        ixx="1.67979856593742E-05"
        ixy="-3.99583945134582E-07"
        ixz="-4.50175601473545E-07"
        iyy="2.22492092782239E-05"
        iyz="-1.73815331900421E-06"
        izz="1.69288828335561E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L31.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L31.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="S3"
    type="revolute">
    <origin
      xyz="0.0594999999999999 0.0539983931640023 -0.019"
      rpy="3.14159265358979 0 -1.5707963267949" />
    <parent
      link="Body" />
    <child
      link="L31" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-2.1"
      upper="0.3"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L32">
    <inertial>
      <origin
        xyz="-0.0152238321171441 -1.5693747225376E-07 0.0464772913413801"
        rpy="0 0 0" />
      <mass
        value="0.0535927277366091" />
      <inertia
        ixx="2.51586895010187E-05"
        ixy="4.86324708459078E-10"
        ixz="-1.10421470951949E-06"
        iyy="2.95873597072862E-05"
        iyz="1.33164835788701E-09"
        izz="1.04825685515283E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L32.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L32.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="E3"
    type="revolute">
    <origin
      xyz="-0.0115016068359978 0 -0.042"
      rpy="2.35619449019235 0 1.5707963267949" />
    <parent
      link="L31" />
    <child
      link="L32" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-1.1"
      upper="1.45"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L33">
    <inertial>
      <origin
        xyz="-0.0155766133039519 0.00786484112620797 0.0325184983163559"
        rpy="0 0 0" />
      <mass
        value="0.0218691445982019" />
      <inertia
        ixx="1.57449330350408E-05"
        ixy="-1.85429515702216E-07"
        ixz="-7.65681275624552E-07"
        iyy="1.89273785292477E-05"
        iyz="9.58348342255634E-07"
        izz="6.56780551793559E-06" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L33.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L33.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="K3"
    type="revolute">
    <origin
      xyz="0 0 0.0674999999999999"
      rpy="1.5707963267949 0 0" />
    <parent
      link="L32" />
    <child
      link="L33" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-3.2"
      upper="0.5"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L34">
    <inertial>
      <origin
        xyz="0.0072466 0.019677 -0.0082129"
        rpy="0 0 0" />
      <mass
        value="0.0048702" />
      <inertia
        ixx="4.7823E-07"
        ixy="-1.5635E-07"
        ixz="-4.7733E-13"
        iyy="3.2701E-07"
        iyz="-3.6519E-13"
        izz="6.9731E-07" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L34.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.79216 0.81961 0.93333 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L34.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="Foot3"
    type="fixed">
    <origin
      xyz="-0.0062871 0.0033624 0.095646"
      rpy="1.5708 0 1.5708" />
    <parent
      link="L33" />
    <child
      link="L34" />
    <axis
      xyz="0 0 1" />
  </joint>
  <link
    name="L41">
    <inertial>
      <origin
        xyz="0.026005455846703 -0.0139117596798611 -0.035793457414895"
        rpy="0 0 0" />
      <mass
        value="0.0542977426736307" />
      <inertia
        ixx="1.67979856593742E-05"
        ixy="-3.99583945134579E-07"
        ixz="-4.50175601473558E-07"
        iyy="2.22492092782239E-05"
        iyz="-1.7381533190042E-06"
        izz="1.69288828335561E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L41.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L41.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="S4"
    type="revolute">
    <origin
      xyz="0.0594999999999999 -0.0555964454822063 -0.019"
      rpy="3.14159265358979 0 -1.5707963267949" />
    <parent
      link="Body" />
    <child
      link="L41" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-2.1"
      upper="0.3"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L42">
    <inertial>
      <origin
        xyz="-0.0152238321171441 -1.56937472260699E-07 0.0464772913413801"
        rpy="0 0 0" />
      <mass
        value="0.0535927277366091" />
      <inertia
        ixx="2.51586895010187E-05"
        ixy="4.86324708458654E-10"
        ixz="-1.10421470951951E-06"
        iyy="2.95873597072862E-05"
        iyz="1.33164835788531E-09"
        izz="1.04825685515283E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L42.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L42.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="E4"
    type="revolute">
    <origin
      xyz="0.0389035545177936 0 -0.042"
      rpy="2.35619449019235 0 1.5707963267949" />
    <parent
      link="L41" />
    <child
      link="L42" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-1.1"
      upper="1.45"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L43">
    <inertial>
      <origin
        xyz="-0.0155766133039519 0.00786484112620803 0.0325184983163559"
        rpy="0 0 0" />
      <mass
        value="0.0218691445982019" />
      <inertia
        ixx="1.57449330350409E-05"
        ixy="-1.85429515702235E-07"
        ixz="-7.65681275624543E-07"
        iyy="1.89273785292478E-05"
        iyz="9.58348342255608E-07"
        izz="6.56780551793557E-06" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L43.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L43.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="K4"
    type="revolute">
    <origin
      xyz="0 0 0.0674999999999999"
      rpy="1.5707963267949 0 0" />
    <parent
      link="L42" />
    <child
      link="L43" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-3.2"
      upper="0.5"
      effort="1.5"
      velocity="6.2" />
  </joint>
  <link
    name="L44">
    <inertial>
      <origin
        xyz="0.0072466 0.019677 -0.0082129"
        rpy="0 0 0" />
      <mass
        value="0.0048702" />
      <inertia
        ixx="4.7823E-07"
        ixy="-1.5635E-07"
        ixz="-4.775E-13"
        iyy="3.2701E-07"
        iyz="-3.6522E-13"
        izz="6.9731E-07" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L44.stl.obj" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.79216 0.81961 0.93333 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="../meshes/L44.stl.obj" />
      </geometry>
    </collision>
  </link>
  <joint
    name="Foot4"
    type="fixed">
    <origin
      xyz="-0.0062871 0.0033624 0.095646"
      rpy="1.5708 0 1.5708" />
    <parent
      link="L43" />
    <child
      link="L44" />
    <axis
      xyz="0 0 1" />
  </joint>
</robot>

I can provide the collision OBJs if necessary. Appreciate any help.

jhwangbo commented 4 years ago

I can't tell much without checking out the mesh files.

dyspr0sium commented 4 years ago

Sure, here are the meshes. The original files from SolidWorks are STL but I converted them to OBJ because there was an error importing the original STL meshes into raisim.

I should add that the URDF, regardless of STL or OBJ meshes, was checked to work correctly in PyBullet.

jhwangbo commented 4 years ago

well, apparently I was wrong about the obj convention. You obj file has a line like v -0.00381818 0.000196837 -0.00616337 There are two spaces after the "v". same for "f". My obj reader can only read if there is only one space... I fixed this is in V1.0 but you can't get this version yet. I suggest just replace all double spaces with a single space. Thank you for reporting this bug

and your meshes seem very fine. This creates so much burden on collision detection. You will lose the benefits of the super-fast dynamics solver of RaiSim with this model...

dyspr0sium commented 4 years ago

Perfect, thank you very much. The issue is resolved after replacing all double spaces with single spaces in the OBJ files.

I will consider replacing the collision boxes with simple shapes if the performance too slow due to the fine meshes.