Question about rotational motion

Official Python bindings with a focus on reinforcement learning and robotics.
Post Reply
tamubun
Posts: 3
Joined: Tue Apr 17, 2018 12:36 pm

Question about rotational motion

Post by tamubun »

I made simple model to check free rotational motion.
model.png
model.png (4.25 KiB) Viewed 3749 times
The masses of Two balls are twice of the mass of white box.
The initial velocities and angular velocities are all 0, and the gravity is also 0.
Only the red ball starts to rotate around upper right corner of the white box with axis aligned top line of the box.
The green ball is fixed to the white box.

When a simulation starts, white box starts to rotate opposite direction of red ball by the counter action, this is natural.
What seems very unnatural is the motion is too stable. Since the heavy red ball rotates around non centre of mass,
I think the white box should show wobble motion, but the simulation says white box only rotates smoothly.

The python code and URDF are as follows. Are there some mistakes?

Code: Select all

import pybullet as p
import time
physicsClient = p.connect(p.GUI)
body = p.loadURDF("b.urdf",0,0,1)
p.changeDynamics(body, -1, linearDamping = 0.0, angularDamping = 0.0)
p.changeDynamics(body, 0, linearDamping = 0.0, angularDamping = 0.0)
p.setJointMotorControl2(
    body, 0, p.VELOCITY_CONTROL,
    targetVelocity = 5, force = 1000
)

while True:
    p.stepSimulation()
    time.sleep(0.01)

Code: Select all

<?xml version="0.0" ?>
<robot name="cube.urdf">
  <link name="baseLink">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="1"/>
      <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="1.0 .4 2.0"/>
      </geometry>
       <material name="white">
        <color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="1.0 .4 2.0"/>
      </geometry>
    </collision>
  </link>

  <link name="ball">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="2"/>
      <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 1"/>
      <geometry>
        <sphere radius="0.2"/>
      </geometry>
       <material name="red">
        <color rgba="1 0 0 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 1"/>
      <geometry>
        <sphere radius="0.2"/>
      </geometry>
    </collision>
  </link>

  <joint name="joint_baseLink_ball" type="continuous">
    <parent link="baseLink"/>
    <child link="ball"/>
    <origin xyz="0.7 0 1"/>
    <axis xyz="1 0 0"/>
  </joint>

  <link name="ball2">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="2"/>
      <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 1"/>
      <geometry>
        <sphere radius="0.2"/>
      </geometry>
       <material name="green">
        <color rgba="0 1 0 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 1"/>
      <geometry>
        <sphere radius="0.2"/>
      </geometry>
    </collision>
  </link>

  <joint name="joint_baseLink_ball2" type="fixed">
    <parent link="baseLink"/>
    <child link="ball2"/>
    <origin xyz="-0.7 0 1"/>
  </joint>
</robot>
tamubun
Posts: 3
Joined: Tue Apr 17, 2018 12:36 pm

Re: Question about rotational motion

Post by tamubun »

I made 2 movies to compare the motion of above model between pybullet and ODE.

pybullet: https://youtu.be/HkX4TijO01c
ODE: https://youtu.be/kDX32Xembo4

I think the simulation of ODE is correct and that of pybullet is not correct.
Are there some options to control?

The code of ODE is follows (modified demo_hinge.cpp)

Code: Select all

/*************************************************************************
 *                                                                       *
 * Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith.       *
 * All rights reserved.  Email: russ@q12.org   Web: www.q12.org          *
 *                                                                       *
 * This library is free software; you can redistribute it and/or         *
 * modify it under the terms of EITHER:                                  *
 *   (1) The GNU Lesser General Public License as published by the Free  *
 *       Software Foundation; either version 2.1 of the License, or (at  *
 *       your option) any later version. The text of the GNU Lesser      *
 *       General Public License is included with this library in the     *
 *       file LICENSE.TXT.                                               *
 *   (2) The BSD-style license that is included with this library in     *
 *       the file LICENSE-BSD.TXT.                                       *
 *                                                                       *
 * This library is distributed in the hope that it will be useful,       *
 * but WITHOUT ANY WARRANTY; without even the implied warranty of        *
 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files    *
 * LICENSE.TXT and LICENSE-BSD.TXT for more details.                     *
 *                                                                       *
 *************************************************************************/

#include <ode/ode.h>
#include <drawstuff/drawstuff.h>
#include "texturepath.h"

#ifdef _MSC_VER
#pragma warning(disable:4244 4305)  // for VC++, no precision loss complaints
#endif

// select correct drawing functions
#ifdef dDOUBLE
#define dsDrawBox dsDrawBoxD
#endif

// dynamics and collision objects
static dWorldID world;
static dBodyID body[3];
static dJointID hinge;
static dJointID fix;

// start simulation - set viewpoint

static void start()
{
  dAllocateODEDataForThread(dAllocateMaskAll);

  static float xyz[3] = {1.6653,-4.1950,1.4700};
  static float hpr[3] = {114.0000,1.0000,0.0000};
  dsSetViewpoint (xyz,hpr);
}

// simulation loop

static void simLoop (int pause)
{
  static int count = 0;
  static int rot = 0;
  static dReal prev = -1.0;

  if (!pause) {
    dWorldQuickStep (world,0.01);
    if ( dJointGetHingeAngle(hinge) < 0 && prev >= 0 ) {
      rot += 1;
      if ( rot >= 2 ) {
        dsStop();
        printf("%d\n", count);
      }
    }
    prev = dJointGetHingeAngle(hinge);
    ++count;
  }

  dReal sides0[3] = {1.0, 0.2, 2.0};
  dsSetColor (1,1,1);
  dsDrawBox (dBodyGetPosition(body[0]),dBodyGetRotation(body[0]),sides0);
  dsSetColor (1,0,0);
  dsDrawSphere (dBodyGetPosition(body[1]),dBodyGetRotation(body[1]),0.2);
  dsSetColor (0,1,0);
  dsDrawSphere (dBodyGetPosition(body[2]),dBodyGetRotation(body[2]),0.2);
}


int main (int argc, char **argv)
{
  // setup pointers to drawstuff callback functions
  dsFunctions fn;
  fn.version = DS_VERSION;
  fn.start = &start;
  fn.step = &simLoop;
  fn.stop = 0;
  fn.path_to_textures = DRAWSTUFF_TEXTURE_PATH;

  // create world
  dInitODE2(0);
  world = dWorldCreate();

  dMass m;
  dMassSetBox (&m, 1, 1.0, 0.4, 2.0);
  dMassAdjust (&m, 1);

  dQuaternion q;
  dQFromAxisAndAngle (q,1,1,0,0.25*M_PI);

  body[0] = dBodyCreate (world);
  dBodySetMass (body[0],&m);
  dBodySetPosition (body[0],0, 0, 2);

  dMass m2;
  dMassSetSphere (&m2, 2, 0.2);
  dMassAdjust (&m, 1);

  body[1] = dBodyCreate (world);
  dBodySetMass (body[1],&m2);
  dBodySetPosition (body[1], 0.7, 0, 4);
  body[2] = dBodyCreate (world);
  dBodySetMass (body[2],&m2);
  dBodySetPosition (body[2], -0.7, 0, 4);

  hinge = dJointCreateHinge (world,0);
  dJointAttach (hinge,body[0],body[1]);
  dJointSetHingeAnchor (hinge,0.7,0,3);
  dJointSetHingeAxis (hinge,1,0,0);
  dJointSetHingeParam(hinge, dParamVel, -5);
  dJointSetHingeParam(hinge, dParamFMax, 1000);

  fix = dJointCreateFixed (world,0);
  dJointAttach (fix,body[0],body[2]);
  dJointSetFixed(fix);

  // run simulation
  dsSimulationLoop (argc,argv,352,288,&fn);

  dWorldDestroy (world);
  dCloseODE();
  return 0;
}
tamubun
Posts: 3
Joined: Tue Apr 17, 2018 12:36 pm

Re: Question about rotational motion

Post by tamubun »

Now I FOUND the problem of my URDF :P

Inertial origins of red and green balls were at (0,0,0) but they should match those of collision origins. So when I use the following URDF, the model properly shows wobble motion. I thought inertial origins were automatically calculated as well as inertia tensors.

Code: Select all

<?xml version="0.0" ?>
<robot name="cube.urdf">
  <link name="baseLink">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="1"/>
      <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="1.0 .4 2.0"/>
      </geometry>
       <material name="white">
        <color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="1.0 .4 2.0"/>
      </geometry>
    </collision>
  </link>

  <link name="ball">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 1"/>
      <mass value="2"/>
      <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 1"/>
      <geometry>
        <sphere radius="0.2"/>
      </geometry>
       <material name="red">
        <color rgba="1 0 0 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 1"/>
      <geometry>
        <sphere radius="0.2"/>
      </geometry>
    </collision>
  </link>

  <joint name="joint_baseLink_ball" type="continuous">
    <parent link="baseLink"/>
    <child link="ball"/>
    <origin xyz="0.7 0 1"/>
    <axis xyz="1 0 0"/>
  </joint>

  <link name="ball2">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 1"/>
      <mass value="2"/>
      <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 1"/>
      <geometry>
        <sphere radius="0.2"/>
      </geometry>
       <material name="green">
        <color rgba="0 1 0 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 1"/>
      <geometry>
        <sphere radius="0.2"/>
      </geometry>
    </collision>
  </link>

  <joint name="joint_baseLink_ball2" type="fixed">
    <parent link="baseLink"/>
    <child link="ball2"/>
    <origin xyz="-0.7 0 1"/>
  </joint>
</robot>
Post Reply