Home | Tutorials | Wiki | Issues
Ask Your Question
1

Setting high damping breaks model

asked 2015-03-23 13:54:02 -0500

I've come across a problem in my models that I'd like an explanation for. For any given joint, if I set damping too high all the parts lock to the origin. I'm guessing this is because it uses damping in some calculation, and it cannot be solved for. Is there a way I can calculate before hand how high is too high for damping?

#I have isolated the issue in the below URDF.

<robot
  name="test_bot">
  <link
    name="chassis">
    <inertial>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <mass
        value="0.1" />
      <inertia
        ixx="0.1"
        ixy="0"
        ixz="0"
        iyy="0.1"
        iyz="0"
        izz="0.1" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <box size="1 1 1"/>
      </geometry>
      <material
        name="">
        <color
          rgba="1 1 0 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <box size="1 1 1"/>
      </geometry>
    </collision>
  </link>

  <link
    name="front_left_wheel">
    <inertial>
      <origin
        xyz="0 0 0.5"
        rpy="0 0 0" />
      <mass
        value="0.1" />
      <inertia
        ixx="0.1"
        ixy="0"
        ixz="0"
        iyy="0.1"
        iyz="0"
        izz="0.1" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <box size="1 1 1"/>
      </geometry>
      <material
        name="">
        <color
          rgba="0.2 0.2 1 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <box size="1 1 1"/>
      </geometry>
    </collision>
  </link>

  <joint
    name="front_left_axel"
    type="continuous">
    <origin
      xyz="0 0 1"/>
      rpy="0 0 0" />
    <parent
      link="chassis" />
    <child
      link="front_left_wheel" />
    <axis
      xyz="0 0 1" />
    <dynamics damping="200" friction="0.5"/>
  </joint>
</robot>
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2015-03-23 14:10:28 -0500

hsu gravatar image

updated 2016-01-26 16:25:29 -0500

make damping implicit by adding

<gazebo reference="front_left_axel">
  <implicitSpringDamper>1</implicitSpringDamper>
</gazebo>

to your model.

Or for example in SDF for ODE:

<joint name="front_left_axel" type="revolute">
    ...
    <physics>
        <ode>
            <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
    </physics>
</joint>
edit flag offensive delete link more
Login/Signup to Answer

Question Tools

1 follower

Stats

Asked: 2015-03-23 13:54:02 -0500

Seen: 1,067 times

Last updated: Jan 26 '16