Gazebo | Ignition | Community
Ask Your Question
0

Object "vibrating" when in contact with other

asked 2020-08-25 12:46:03 -0500

yuril gravatar image

I want to simulate two differential drive robots carrying a box above their chassis. But I am having some trouble on the simulation because the box is vibrating when above the robots.

This is the sdf from the box, am I doing something wrong or is this expected? How could I correct it?

<sdf version="1.4"> <model name="box"> <static>false</static> <link name="chassis"> <pose>0 0 0 0 0 0</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.001666666</ixx> <ixy>0.0</ixy><iyy>0.001416666</iyy> <ixz>0.0</ixz><iyz>0.0</iyz><izz>0.001666666</izz> </inertia> </inertial> <collision name="collision"> <geometry> <box> <size>.1 .4 .1</size> </box> </geometry> <surface> <friction> <ode> <mu>10000</mu> <mu2>10000</mu2> </ode> </friction> </surface> </collision> <visual name="visual"> <geometry> <box> <size>.1 .4 .1</size> </box> </geometry> </visual> </link> </model> </sdf>

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-08-25 17:31:07 -0500

Try setting min_depth in your model like so

<surface>
  <contact>
    <ode>
      <min_depth>0.001</min_depth>
    </ode>
  </contact>
  <friction>
    <ode>
       <mu>10000</mu>
       <mu2>10000</mu2>
    </ode>
  </friction>
</surface>

Other contact parameters of interest might be kp and kd.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-08-25 12:46:03 -0500

Seen: 476 times

Last updated: Aug 25 '20