0

I'm trying to model a small and light objects(the links of a rope). This is an example sdf. If I decrease the mass from 1.0 to 0.3 and adjust the inertias accordingly, it seems to disappear off the screen as soon as it touches the ground. With more links, I also get

RuntimeError: MultibodyPlant's discrete update solver failed to converge at simulation time =   0.004 with discrete update period =   0.001. This usually means that the plant's discrete update period is too large to resolve the system's dynamics for the given simulation conditions. This is often the case during abrupt collisions or during complex and fast changing contact configurations. Another common cause is the use of high gains in the simulation of closed loop systems. These might cause numerical instabilities given our discrete solver uses an explicit treatment of actuation inputs. Possible solutions include:
  1. reduce the discrete update period set at construction,
  2. decrease the high gains in your controller whenever possible,
  3. switch to a continuous model (discrete update period is zero),      though this might affect the simulation run time.

or

terminated by signal SIGSEGV (Address boundary error)

I can work around a lot of these issues if I don't compute physically accurate inertias or if I put a mass of 1(and large inertias) on the dummy link, but I'm wondering if there's a proper way to resolve these errors. I'll also add that I'm not seeing weird behavior for a single link.

SDF: 2 links with mass 1kg

<sdf version='1.6'>
    <model name='capsule'>
  <link name="capsule_1">
      <pose> 0 0 2.0 0 0 0</pose>
      <inertial>
        <pose frame=''>0 0 -0.05 0 0 0</pose>
        <mass>1.0</mass>
        <inertia>
          <ixx>0.0008395833333333335</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0008395833333333335</iyy>
          <iyz>0</iyz>
          <izz>1.25e-05</izz>
        </inertia>
      </inertial>
      <visual name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>
        <material>
          <diffuse>0.5569 0.349 0.2353 1.0</diffuse>
        </material>
      </visual>

      <collision name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>

        <surface>
          <friction>
          <ode>
            <mu>0.0</mu>
            <mu2>0.0</mu2>
          </ode>
          </friction>
        </surface>
      </collision>

  </link>
  <link name="capsule_2">
      <pose> 0 0 1.9 0 0 0</pose>
      <inertial>
        <pose frame=''>0 0 -0.05 0 0 0</pose>
        <mass>1.0</mass>
        <inertia>
          <ixx>0.0008395833333333335</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0008395833333333335</iyy>
          <iyz>0</iyz>
          <izz>1.25e-05</izz>
        </inertia>
      </inertial>
      <visual name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>
        <material>
          <diffuse>0.5569 0.349 0.2353 1.0</diffuse>
        </material>
      </visual>

      <collision name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>

        <surface>
          <friction>
          <ode>
            <mu>0.0</mu>
            <mu2>0.0</mu2>
          </ode>
          </friction>
        </surface>
      </collision>

  </link>
  <link name="capsule_1_extra">
    <pose> 0 0 1.9 0 0 0 </pose>
    <inertial>
      <pose frame=''>0 0 0 0 0 0 </pose>
      <mass>1e-10</mass>
      <inertia>
        <ixx>1e-10</ixx>
        <ixy>0</ixy>
        <ixz>0</ixz>
        <iyy>1e-10</iyy>
        <iyz>0</iyz>
        <izz>1e-10</izz>
      </inertia>
    </inertial>
  </link>
  <joint name="capsule_1_capsule_2_joint_x" type="revolute">
    <pose> 0 0 0 0 0 0 </pose>
    <child>capsule_2</child>
    <parent>capsule_1_extra</parent>
    <axis>
      <xyz> 1 0 0 </xyz>
      <limit>
        <effort>0</effort>
        <lower>-0.5</lower>
        <upper>0.5</upper>
      </limit>
      <dynamics>
        <damping> 1 </damping>
        <friction> 0 </friction>
        <spring_reference> 0 </spring_reference>
        <spring_stiffness> 0.0 </spring_stiffness>
      </dynamics>
      <use_parent_model_frame>1</use_parent_model_frame>
    </axis>
  </joint>

  <joint name="capsule_1_capsule_2_joint_y" type="revolute">
    <pose> 0 0 0 0 0 0 </pose>
    <child>capsule_1_extra</child>
    <parent>capsule_1</parent>
    <axis>
      <xyz> 0 1 0 </xyz>
      <limit>
        <effort>0</effort>
        <lower>-0.5</lower>
        <upper>0.5</upper>
      </limit>
      <dynamics>
        <damping> 1 </damping>
        <friction> 0 </friction>
        <spring_reference> 0 </spring_reference>
        <spring_stiffness> 0.0 </spring_stiffness>
      </dynamics>
      <use_parent_model_frame>1</use_parent_model_frame>
    </axis>
  </joint>
    </model>
</sdf>

SDF: 2 links with mass 0.3kg

<sdf version='1.6'>
    <model name='capsule'>
  <link name="capsule_1">
      <pose> 0 0 2.0 0 0 0</pose>
      <inertial>
        <pose frame=''>0 0 -0.05 0 0 0</pose>
        <mass>0.3</mass>
        <inertia>
          <ixx>0.00025187500000000004</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.00025187500000000004</iyy>
          <iyz>0</iyz>
          <izz>3.75e-06</izz>
        </inertia>
      </inertial>
      <visual name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>
        <material>
          <diffuse>0.5569 0.349 0.2353 1.0</diffuse>
        </material>
      </visual>

      <collision name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>

        <surface>
          <friction>
          <ode>
            <mu>0.0</mu>
            <mu2>0.0</mu2>
          </ode>
          </friction>
        </surface>
      </collision>

  </link>
  <link name="capsule_2">
      <pose> 0 0 1.9 0 0 0</pose>
      <inertial>
        <pose frame=''>0 0 -0.05 0 0 0</pose>
        <mass>0.3</mass>
        <inertia>
          <ixx>0.00025187500000000004</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.00025187500000000004</iyy>
          <iyz>0</iyz>
          <izz>3.75e-06</izz>
        </inertia>
      </inertial>
      <visual name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>
        <material>
          <diffuse>0.5569 0.349 0.2353 1.0</diffuse>
        </material>
      </visual>

      <collision name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>

        <surface>
          <friction>
          <ode>
            <mu>0.0</mu>
            <mu2>0.0</mu2>
          </ode>
          </friction>
        </surface>
      </collision>

  </link>
  <link name="capsule_1_extra">
    <pose>0 0 1.9 0 0 0</pose>
    <inertial>
      <pose frame=''>0 0 0 0 0 0 </pose>
      <mass>1e-10</mass>
      <inertia>
        <ixx>1e-10</ixx>
        <ixy>0</ixy>
        <ixz>0</ixz>
        <iyy>1e-10</iyy>
        <iyz>0</iyz>
        <izz>1e-10</izz>
      </inertia>
    </inertial>
  </link>
  <joint name="capsule_1_capsule_2_joint_x" type="revolute">
    <pose> 0 0 0 0 0 0 </pose>
    <child>capsule_2</child>
    <parent>capsule_1_extra</parent>
    <axis>
      <xyz> 1 0 0 </xyz>
      <limit>
        <effort>0</effort>
        <lower>-3.14</lower>
        <upper>3.14</upper>
      </limit>
      <dynamics>
        <damping> 1 </damping>
        <friction> 0 </friction>
        <spring_reference> 0 </spring_reference>
        <spring_stiffness> 10 </spring_stiffness>
      </dynamics>
      <use_parent_model_frame>1</use_parent_model_frame>
    </axis>
  </joint>

  <joint name="capsule_1_capsule_2_joint_y" type="revolute">
    <pose> 0 0 0 0 0 0 </pose>
    <child>capsule_1_extra</child>
    <parent>capsule_1</parent>
    <axis>
      <xyz> 0 1 0 </xyz>
      <limit>
        <effort>0</effort>
        <lower>-3.14</lower>
        <upper>3.14</upper>
      </limit>
      <dynamics>
        <damping> 1 </damping>
        <friction> 0 </friction>
        <spring_reference> 0 </spring_reference>
        <spring_stiffness> 10 </spring_stiffness>
      </dynamics>
      <use_parent_model_frame>1</use_parent_model_frame>
    </axis>
  </joint>
    </model>
</sdf>
<sdf version='1.6'>
    <model name='capsule'>
  <link name="capsule_1">
      <pose> 0 0 2.0 0 0 0</pose>
      <inertial>
        <pose frame=''>0 0 -0.05 0 0 0</pose>
        <mass>0.3</mass>
        <inertia>
          <ixx>0.00025187500000000004</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.00025187500000000004</iyy>
          <iyz>0</iyz>
          <izz>3.75e-06</izz>
        </inertia>
      </inertial>
      <visual name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>
        <material>
          <diffuse>0.5569 0.349 0.2353 1.0</diffuse>
        </material>
      </visual>

      <collision name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>

        <surface>
          <friction>
          <ode>
            <mu>0.0</mu>
            <mu2>0.0</mu2>
          </ode>
          </friction>
        </surface>
      </collision>

  </link>
  <link name="capsule_2">
      <pose> 0 0 1.9 0 0 0</pose>
      <inertial>
        <pose frame=''>0 0 -0.05 0 0 0</pose>
        <mass>0.3</mass>
        <inertia>
          <ixx>0.00025187500000000004</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.00025187500000000004</iyy>
          <iyz>0</iyz>
          <izz>3.75e-06</izz>
        </inertia>
      </inertial>
      <visual name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>
        <material>
          <diffuse>0.5569 0.349 0.2353 1.0</diffuse>
        </material>
      </visual>

      <collision name='cylinder'>
        <pose frame=''> 0 0 -0.05 0 0 0 </pose>
        <geometry>
          <cylinder>
          <radius>0.005</radius>
          <length>0.1</length>
          </cylinder>
        </geometry>

        <surface>
          <friction>
          <ode>
            <mu>0.0</mu>
            <mu2>0.0</mu2>
          </ode>
          </friction>
        </surface>
      </collision>

  </link>
  <link name="capsule_1_extra">
    <pose>0 0 1.9 0 0 0</pose>
    <inertial>
      <pose frame=''>0 0 0 0 0 0 </pose>
      <mass>1e-10</mass>
      <inertia>
        <ixx>1e-10</ixx>
        <ixy>0</ixy>
        <ixz>0</ixz>
        <iyy>1e-10</iyy>
        <iyz>0</iyz>
        <izz>1e-10</izz>
      </inertia>
    </inertial>
  </link>
  <joint name="capsule_1_capsule_2_joint_x" type="revolute">
    <pose> 0 0 0 0 0 0 </pose>
    <child>capsule_2</child>
    <parent>capsule_1_extra</parent>
    <axis>
      <xyz> 1 0 0 </xyz>
      <limit>
        <effort>0</effort>
        <lower>-3.14</lower>
        <upper>3.14</upper>
      </limit>
      <dynamics>
        <damping> 1 </damping>
        <friction> 0 </friction>
        <spring_reference> 0 </spring_reference>
        <spring_stiffness> 10 </spring_stiffness>
      </dynamics>
      <use_parent_model_frame>1</use_parent_model_frame>
    </axis>
  </joint>

  <joint name="capsule_1_capsule_2_joint_y" type="revolute">
    <pose> 0 0 0 0 0 0 </pose>
    <child>capsule_1_extra</child>
    <parent>capsule_1</parent>
    <axis>
      <xyz> 0 1 0 </xyz>
      <limit>
        <effort>0</effort>
        <lower>-3.14</lower>
        <upper>3.14</upper>
      </limit>
      <dynamics>
        <damping> 1 </damping>
        <friction> 0 </friction>
        <spring_reference> 0 </spring_reference>
        <spring_stiffness> 10 </spring_stiffness>
      </dynamics>
      <use_parent_model_frame>1</use_parent_model_frame>
    </axis>
  </joint>
    </model>
</sdf>

1 Answers1

1

That error is usually caused because our discrete solver fails. As the message suggests, did you attempt to reduce the discrete period (aka time step) at construction of the MultibodyPlant? What I imagine happens here is that your small links lead to fast dynamics and therefore you need smaller time steps to resolve it.

The link dissapearing is most likely due to the fact that the visualizer is already plotting a bad state (diverged, possibly with lots of NaNs). So the visualizer alone won't tell you much.

When setting up the discrete solver you always need an estimation of you system's time scale, stemming from the physics you want to resolve. For your case, and only because I don't know if you have applied forces, thinking of each link as a simple pendulum would allow you to estimate a time scale by for instance computing the period of that pendulum.

With your numbers, for a physical pendulum with inertia Iyy = 0.001 (about the link's end, motion about z seems restricted by your joints), m = 0.3, R=0.05 (distance to COM), I get a compound pendulum effective length of L = I/(m*R) = 0.0667 m. With this I get a period T = 2*pi*sqrt(L/g) = 0.52 seconds. Say I'd take 500 steps per period, then I'd estimate a time step of dt = 1ms.

That's a very rough estimate given I know nothing about your system or external forces. But summarizing, I believe your problem is the plant's time step.

Edit

What about penetration allowance? (MultibodyPlant::set_penetration_allowance()). When contact is present MultibodyPlant::get_contact_penalty_method_time_scale() will give you an estimate of the time scale due to contact. Usually you need to set a time step that is able to comfortably resolve that dynamics.

Alejandro
  • 1,064
  • 1
  • 8
  • 22