Gazebo | Ignition | Community
Ask Your Question
0

not realistic simulatoin

asked 2015-02-02 04:32:18 -0600

djou07 gravatar image

Hi,

I am trying to simulate robots using neural networks and genetic algorithms. here is the link to the video.

I don't know why when the two legs being in the air the cube link don't fall down like it should be in real life. even if I put its mass to 100. The gravity is set as default.

I know that the real time factor can affect, but what are other properties that I have to adjust ?

thank you very much !

here is the SDF file :

<?xml version='1.0'?>
<sdf version='1.4'>
<model name="fourlegs">

  <static>false</static>

  <!--**********************body************************************-->
  <link name='corps'>
      <pose>0 0 .04 0 0 0</pose>

      <inertial>
        <mass>100</mass> 
      </inertial>

      <collision name='collision'>
       <geometry>
        <box>
         <size>.1 .1 .02</size>
        </box>
       </geometry>
     </collision>

     <visual name='visual'>
      <geometry>
       <box>
         <size>.1 .1 .02</size>
       </box>
      </geometry>             
     </visual>
</link>
<!--*********************left leg *******************************-->
<link name='jambeDG'>
<pose> .06 .04 .01 0 0 0</pose>

<inertial>
  <mass>10</mass> 
</inertial>
<collision name='collision'>
  <geometry>
    <box>
      <size>.02 .02 .06</size>
    </box>
  </geometry>
</collision>

<visual name='visual'>
  <geometry>
    <box>
     <size>.02 .02 .06</size>
    </box>
  </geometry>             
</visual>  
</link>
<!--*********************right leg*******************************-->
 <link name='jambeDD'>
  <pose> -.06 .04 .01 0 0 0</pose>

<inertial>
  <mass>10</mass>
</inertial>

<collision name='collision'>
  <geometry>
    <box>
      <size>.02 .02 .06</size>
    </box>
  </geometry>
</collision>

<visual name='visual'>
  <geometry>
    <box>
      <size>.02 .02 .06</size>
    </box>
  </geometry>             
</visual>
</link>

<!--*************************************************************-->
<!--**********************JOINTS*********************************-->
<!--*************************************************************-->

<!--**********************joint left leg************************-->
<joint type="revolute" name="jointJambDG">

<pose> -.01 .0 .03 0 0 0</pose> 

<child>jambeDG</child>
<parent>corps</parent>
<axis>
  <xyz>1 0 0</xyz>
  </axis>
</joint>
<!--**********************joint right leg************************-->
<joint type="revolute" name="jointJambDD">
 <pose> .01 .0 .03 0 0 0</pose>
 <child>jambeDD</child>
 <parent>corps</parent>
 <axis>
   <xyz>1 0 0</xyz>  
   </axis>
</joint>
</model>
</sdf>
edit retag flag offensive close merge delete

Comments

1

One thing that could help is setting the inertia matrix for each link. [This tutorial](http://gazebosim.org/tutorials?tut=inertia&cat=build_robot) should help.

chapulina gravatar imagechapulina ( 2015-02-02 10:30:26 -0600 )edit

3 Answers

Sort by ยป oldest newest most voted
1

answered 2015-02-05 13:06:55 -0600

hsu gravatar image

What you are seeing is the dynamics for the default moment inertia (I = identity matrix) when a more physically realistic one is not specified. My suggestion is to update the models with realistic MOI using equations from references such as this one based on object mass, size and density distribution.

edit flag offensive delete link more

Comments

Thanks for your answer. I set up the inertia properties like shown in the wiki page. But when I give joints a 0.1 force and 0.1 velocity the robot starts to jump and pounce with a fast way, not realistic at all, I don't know if it's the gravity or ground friction ?! I will try Ricardo Tellez's approach and see...

djou07 gravatar imagedjou07 ( 2015-03-07 03:23:14 -0600 )edit
1

answered 2015-02-23 09:20:47 -0600

The key to have realistic simulations is to provide a correct section <inertias> ... </inertias>

A proper section should look like this:

<inertia> <!-- interias are tricky to compute -->
      <!-- http://answers.gazebosim.org/question/4372/the-inertia-matrix-explained/ -->
      <ixx>0.000033719</ixx>       <!-- for a box: ixx = 0.083 * mass * (y*y + z*z) -->
      <ixy>0.0</ixy>         <!-- for a box: ixy = 0 -->
      <ixz>0.0</ixz>         <!-- for a box: ixz = 0 -->
      <iyy>0.001305175</iyy>       <!-- for a box: iyy = 0.083 * mass * (x*x + z*z) -->
      <iyz>0.0</iyz>         <!-- for a box: iyz = 0 -->
      <izz>0.001322294</izz>       <!-- for a box: izz = 0.083 * mass * (x*x + y*y) -->
    </inertia>
  </inertial>

Steps to follow:

0- Use Blender to automatically set the center of mass and arrange the axis of the object at that center (this will make later steps easier) 1- Use the tutorial chapulina has suggested to calculate the inertial parameters and set the model. Don't forget to set a correct mass value (the one you have now seems unrealistic) 2- Use Gazebo's option View->Center of mass/Inertia to observe if your inertias are correct (see figures attached for a wrong one an a correct one, for a spoon) 3- If they do not show correct, iterate

INCORRECT INERTIAS image description

CORRECT INERTIAS image description

edit flag offensive delete link more

Comments

thanks for your answer, I will try that out

djou07 gravatar imagedjou07 ( 2015-03-07 09:47:57 -0600 )edit
0

answered 2015-02-24 03:03:08 -0600

I do agree with you Hsu, you approach is closer to reality and may be required in some simulations. From my experience the bounding box approach and center-of-mass calculated as homogeneous body has been good enough for what I needed. Is up to the user to decide, though.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2015-02-02 04:32:18 -0600

Seen: 959 times

Last updated: Feb 24 '15