Page 1 of 1

stepSimulation() not equivalent to setRealTimeSimulation(1)

Posted: Fri Apr 03, 2020 2:31 am
by avandekleut
I want to control a procedurally generated robot. Consider the following code:

Code: Select all

import time
import pybullet as p
import pybullet_data
import sys

physicsClient = p.connect(p.GUI)
p.setPhysicsEngineParameter(enableFileCaching=0)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.resetSimulation()
p.setGravity(0, 0, -10)
planeId = p.loadURDF("plane.urdf")
robot = p.loadURDF(sys.argv[1], [0, 0, 2])
p.setRealTimeSimulation(1)
for t in range(200000):
    p.getKeyboardEvents()

p.resetSimulation()
p.setGravity(0, 0, -10)
planeId = p.loadURDF("plane.urdf")
robot = p.loadURDF(sys.argv[1], [0, 0, 2])
p.setRealTimeSimulation(0)
for t in range(200000):
    p.stepSimulation()
    time.sleep(1. / 240.)
p.disconnect()
The first half runs fine. The second half, my URDF file goes crazy and flies off. Example URDF files that have this behaviour:
https://raw.githubusercontent.com/avand ... ter/2.urdf
https://raw.githubusercontent.com/avand ... ter/1.urdf

Am I misunderstanding something here? What is going on? Why are the two so different?


Edit:

I tried this code using some of the sample URDF files provided and they seem to work alright. There must be some issue in processing the physics of my URDF files.

Re: stepSimulation() not equivalent to setRealTimeSimulation(1)

Posted: Tue Apr 07, 2020 7:44 pm
by Erwin Coumans
Testing here there is no difference between stepSimulation and setRealTimeSimulation, both show instable motion due to a degenerate urdf file.

Those are urdf files with degenerate values. Avoid too small mass (keep it either 0 or in range 0.01 to 100 or so)
avoid large rpy angles, don't use collision shapes with extreme small radius (use 0.05 smallest for a start)

Here is a working version:

Code: Select all

<?xml version="1.0"?>
<robot name="robots/1">
  <link name="8325804">
    <inertial>
      <origin xyz="-5.421010862427522e-20 -1.6263032587282567e-19 0.0010000000000000002" rpy="0 0 0"/>
      <mass value="1"/>
      <inertia ixx="1.675516081914556e-17" ixy="0" ixz="0" iyy="1.675516081914556e-17" iyz="0" izz="1.675516081914556e-17"/>
    </inertial>
    <collision>
      <origin xyz="-5.421010862427522e-20 -1.6263032587282567e-19 0.0010000000000000002" rpy="0 0 0"/>
      <geometry>
        <sphere radius="0.1"/>
      </geometry>
    </collision>
  </link>
  <link name="4735681">
    <inertial>
      <origin xyz="-3.469446951953614e-18 -1.214306433183765e-17 0.08472517387841258" rpy="0 0 0"/>
      <mass value="0.6946108199226944"/>
      <inertia ixx="0.0019944652455508296" ixy="0" ixz="0" iyy="0.0019944652455508296" iyz="0" izz="0.0019944652455508296"/>
    </inertial>
    <collision>
      <origin xyz="-3.469446951953614e-18 -1.214306433183765e-17 0.08472517387841258" rpy="0 0 0"/>
      <geometry>
        <sphere radius="0.08472517387841255"/>
      </geometry>
    </collision>
  </link>
  <link name="4064029">
    <inertial>
      <origin xyz="-0.013392437970720003 6.841951323297693e-05 0.036824153984054794" rpy="0 0 0"/>
      <mass value="0.32657421908334666"/>
      <inertia ixx="0.0003600348756754367" ixy="0" ixz="0" iyy="0.0003600348756754367" iyz="0" izz="0.00022142031140993636"/>
    </inertial>
    <collision>
      <origin xyz="-0.013392437970720003 6.841951323297693e-05 0.036824153984054794" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.0368241539840548" length="0.09571551589530464"/>
      </geometry>
    </collision>
  </link>
  <link name="5314437">
    <inertial>
      <origin xyz="-8.890457814381136e-18 -1.0408340855860843e-17 0.04736004193466575" rpy="0 0 0"/>
      <mass value="0.14423106891506815"/>
      <inertia ixx="0.00012940259033819833" ixy="0" ixz="0" iyy="0.00012940259033819833" iyz="0" izz="0.00012940259033819833"/>
    </inertial>
    <collision>
      <origin xyz="-8.890457814381136e-18 -1.0408340855860843e-17 0.04736004193466575" rpy="0 0 0"/>
      <geometry>
        <sphere radius="0.047360041934665746"/>
      </geometry>
    </collision>
  </link>
  <link name="1844789">
    <inertial>
      <origin xyz="-0.01302201858425922 5.847181364028571e-06 0.009928035035897393" rpy="0 0 0"/>
      <mass value="0.022543488066187885"/>
      <inertia ixx="1.8224520051453555e-05" ixy="0" ixz="0" iyy="1.8224520051453555e-05" iyz="0" izz="1.111009366082133e-06"/>
    </inertial>
    <collision>
      <origin xyz="-0.01302201858425922 5.847181364028571e-06 0.009928035035897393" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.09928035035897387" length="0.09698090677467489"/>
      </geometry>
    </collision>
  </link>
  <link name="3416624">
    <inertial>
      <origin xyz="0.006343136646001411 0.018183987579849615 0.06582443936436896" rpy="0 0 0"/>
      <mass value="0.8541329457565685"/>
      <inertia ixx="0.0020295629099782607" ixy="0" ixz="0" iyy="0.001257342235037602" iyz="0" izz="0.0020295629099782607"/>
    </inertial>
    <collision>
      <origin xyz="0.006343136646001411 0.018183987579849615 0.06582443936436896" rpy="0 0 0"/>
      <geometry>
        <capsule radius="0.05818503294385344" length="0.04143685882263688"/>
      </geometry>
    </collision>
  </link>
  <joint name="2951283" type="continuous">
    <origin xyz=" 0.0001594  -0.00093199  0.00132557" rpy="0 0 0"/>
    <parent link="8325804"/>
    <child link="4735681"/>
    <axis xyz="0 0 1"/>
    <dynamics damping="0.1" friction="0.1"/>
    <limit lower="0" upper="0" effort="1" velocity="1"/>
  </joint>
  <joint name="2574580" type="fixed">
    <origin xyz=" 0.04142879 -0.06828364  0.0564523 " rpy="0 0 0"/>
    <parent link="4735681"/>
    <child link="4064029"/>
    <axis xyz="0 0 0"/>
    <dynamics damping="0" friction="0"/>
    <limit lower="0" upper="0" effort="10" velocity="10"/>
  </joint>
  <joint name="9958721" type="revolute">
    <origin xyz="-1.94187710e-02  2.18095641e-04  1.91914661e-07" rpy="0 0 0"/>
    <parent link="4064029"/>
    <child link="5314437"/>
    <axis xyz="0 0 1"/>
    <dynamics damping="0.1" friction="0.1"/>
    <limit lower="0" upper="6.283185307179586" effort="1" velocity="1"/>
  </joint>
  <joint name="3283812" type="continuous">
    <origin xyz="-0.00912397 -0.04638031  0.04442856" rpy="0 0 0"/>
    <parent link="5314437"/>
    <child link="1844789"/>
    <axis xyz="0 0 1"/>
    <dynamics damping="0.1" friction="0.1"/>
    <limit lower="0" upper="0" effort="1" velocity="1"/>
  </joint>
  <joint name="7781930" type="fixed">
    <origin xyz="-5.21927538e-02  3.11575316e-05  3.00292219e-09" rpy="0 0 0"/>
    <parent link="1844789"/>
    <child link="3416624"/>
    <axis xyz="0 0 0"/>
    <dynamics damping="0" friction="0"/>
    <limit lower="0" upper="0" effort="10" velocity="10"/>
  </joint>
</robot>