Gazebo | Ignition | Community
Ask Your Question
0

How to solve the jitter of model which has link with a picture?

asked 2020-07-10 03:48:34 -0500

this post is marked as community wiki

This post is a wiki. Anyone with karma >75 is welcome to improve it.

Hello,guys! I create a gazebo model ,which has a link with covering a picture.The codes like:image description

<?xml version="1.0" ?>
<sdf version="1.5">
  <model name="forkboardbbb">
    <static>false</static>
    <link name='baselink'>
        <pose>0 0 0 0 0 0</pose>
        <inertial>
           <mass>104</mass>
            <pose>0.5 0.6 0.4 0 0 0</pose>
            <inertia>
        <ixx>85.8</ixx>
        <ixy>34.2</ixy>
        <ixz>29.4</ixz>
        <iyy>75.4</iyy>
        <iyz>29.5</iyz>
        <izz>89.7</izz>
        </inertia>
    </inertial>
        <collision name='collision'>
          <geometry>
      <mesh>
        <scale>1 1 1</scale>
        <uri>model://forkboardbbb/meshes/forkboard112.STL</uri>
      </mesh>
          </geometry>
              <surface>
    <friction>
      <ode>
        <mu>200</mu>
        <mu2>200</mu2>
      </ode>
    </friction>
  </surface>
        </collision>
    <visual name='visual'>
      <geometry>
        <mesh>
          <scale>1 1 1</scale>
          <uri>model://forkboardbbb/meshes/forkboard112.STL</uri>
        </mesh>
      </geometry>
      <material>
        <script>
          <name>Gazebo/White</name>
          <uri>file://media/materials/scripts/gazebo.material</uri>
        </script>
      </material>
    </visual>
</link>  
<!--picture_link-->
    <joint type="fixed" name="link1joint">
      <pose>0 0 0 0 0 0</pose>
      <child>link1</child>
      <parent>baselink</parent>
    </joint>
    <link name="link1">
        <pose>0.5 0.044 -0.062 0 0 0</pose>
    <inertial>
       <mass>0.01</mass>
        <pose>0 0 0 0 0 0</pose>
        <inertia>
        <ixx>1</ixx>
        <ixy>0</ixy>
        <ixz>0</ixz>
        <iyy>1</iyy>
        <iyz>0</iyz>
        <izz>1</izz>
        </inertia>
    </inertial>
        <visual name="visual">
           <pose>0 0 0 0 0 0</pose>
          <geometry>
            <box>
              <size>0.09 0.09 0.09</size>
            </box>
          </geometry>
          <material>
           <script>
              <uri>model://forkboardbbb/materials/scripts1</uri>
              <uri>model://forkboardbbb/materials/textures1</uri>
               <name>Box1/Diffuse</name>
           </script>
           </material>
       </visual>
        <collision name='collision'>
          <geometry>
            <box>
              <size>0.09 0.09 0.09</size>
            </box>
    </geometry>
     </collision>
     </link>
  </model>
</sdf>

When load the model into gazebo,I find that the model is jitter all the time(test by gazebo-view-contacts ). If removed the code

<joint type="fixed" name="link1joint">
  <pose>0 0 0 0 0 0</pose>
  <child>link1</child>
  <parent>baselink</parent>
</joint>

,the jitter of model in gazebo disappeared. If do that,the picture cant be on target position.So,how should I do to solve the jitter ?Or,how should I do to create a gazebo model without jitter, which has a specific picture(size,etc) in target position .I tried to fix the problem by modifying the physical properties, but it didn't work.All files are in this link:https://www.dropbox.com/sh/yewweif4ilqj5qh/AABOt1w2zEfP0aZpZDJCuOe_a?dl=0

Of course, I created my model with reference to beer gazebo model. I'm looking forword to your reply.Thank you in advance.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-07-10 14:14:51 -0500

Contacts usually stabilize when you set a non-zero min_depth.

Adding this to your base link does the trick:

<collision name="collision">
  ...
  <surface>
    ...
    <contact>
      <ode>
        <min_depth>0.001</min_depth>
      </ode>
    </contact>
  </surface>
</collision>
edit flag offensive delete link more

Comments

Thank you very much for your reply. It really solves my problem.Thanks again.

ylh gravatar imageylh ( 2020-07-12 21:27:46 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-07-10 03:48:34 -0500

Seen: 1,018 times

Last updated: Jul 10 '20