In the gazebo environment, once dynamic parameters are added to the urdf model, the connecting rod will be fixed at the origin.

asked 2020-01-31 22:25:43 -0500

this post is marked as community wiki

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

In the gazebo environment, once dynamic parameters are added to the urdf model, the link will be fixed at the origin.

After adding the dynamics damping,the showed link will be fixed at the origin(or maybe world).

<dynamics damping="0.7"/>

before adding the dynamics damping: image description

after adding the dynamics damping: image description

All urde files :

    <?xml version="1.0" encoding="utf-8"?>


       <!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) 
             Commit Version: 1.5.1-0-g916b5db  Build Version: 1.5.7152.31018
             For more information, please see http://wiki.ros.org/sw_urdf_exporter -->


        <!-- Revolute-Revolute Manipulator -->
            <robot name="link" xmlns:xacro="http://www.ros.org/wiki/xacro">

              <!-- Import all Gazebo-customization elem

        ents, including Gazebo colors -->


       <xacro:include filename="$(find link)/urdf/link.gazebo" />

          <!-- Used for fixing robot to Gazebo 'base_link' -->
          <link name="world"/>

      <joint name="fixed" type="fixed">
        <parent link="world"/>
        <child link="base_link"/>
      </joint>

      <link
        name="base_link">
    <inertial>
      <origin
        xyz="5.41431391044674E-19 -3.81599768090245E-18 0.0119651355617924"
        rpy="0 0 0" />
      <mass
        value="0.317346214028947" />
      <inertia
        ixx="0.000400193890599361"
        ixy="-3.73238496454284E-22"
        ixz="-4.8058493695367E-21"
        iyy="0.000399358915837397"
        iyz="-4.57713225377642E-20"
        izz="0.000705715767674914" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://link/meshes/base_link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="1 1 1 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://link/meshes/base_link.STL" />
      </geometry>
    </collision>
  </link>
  <link
    name="link1">
    <inertial>
      <origin
        xyz="0.05 1.04083408558608E-17 0"
        rpy="0 0 0" />
      <mass
        value="0.0335342917352885" />
      <inertia
        ixx="2.87735927381987E-06"
        ixy="2.32934060494933E-21"
        ixz="2.30346855521167E-22"
        iyy="3.89630886120412E-05"
        iyz="1.52906451041926E-23"
        izz="4.12815430236062E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://link/meshes/link1.STL" />
      </geometry>
      <material


name="">
    <color
      rgba="1 1 1 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://link/meshes/link1.STL" />
  </geometry>
    </collision>
  </link>
  <joint
    name="joint1"
    type="continuous">
    <origin
      xyz="0 0 0.06"
      rpy="-1.5708 -1.033 0" />
    <parent
      link="base_link" />
    <child
      link="link1" />
    <axis
      xyz="0 0 -1" />
    <dynamics damping="0.7"/>
  </joint>
  <link
    name="link2">
    <inertial>
      <origin
        xyz="0.0847185207825683 -7.7715611723761E-16 -5.85317276699049E-18"
        rpy="0 0 0" />
      <mass
        value="0.0777109513774519" />
      <inertia
        ixx="9.11722126446958E-06"
        ixy="6.56450534122083E-21"
        ixz="2.83871210352196E-21"
        iyy="0.0003324057043755"
        iyz="7.17448377804427E-22"
        izz="0.000335193630705286" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://link/meshes/link2.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="1 1 1 1" />
      </material>
    </visual>


     <collision>
          <origin
            xyz="0 0 0"
            rpy="0 0 0" />
          <geometry>
            <mesh
              filename="package://link/meshes/link2.STL" />
          </geometry>
        </collision>
      </link>

          <joint
            name="joint2"
            type="continuous">
            <origin
              xyz="0.1 0 0"
              rpy="0 0 0.85898" />
            <parent
              link="link1" />
            <child
          link="link2" />
        <axis
          xyz="0 0 -1" />
        <dynamics damping="0.7"/>
      </joint>




</robot>

What is the cause of this? How to properly add dynamic parameters, including joint ... (more)

edit retag flag offensive close merge delete