Gazebo | Ignition | Community
Ask Your Question
0

model contact with ground issue

asked 2020-02-15 14:00:07 -0500

TorontoRoboticsClub gravatar image

updated 2020-02-15 14:20:33 -0500

Hello,

I am running Gazebo7 ver 7.16 in Ubuntu 16.04 and Ros Kinetic.

I have a four wheeled robot that I am trying to simulate in Gazebo:

image description

The two front castor wheels are behaving "strange". I believe there are two issues and they are related:

Issue #1 - Dancing / moving / rotating I took pictures of the model in with no commands being given to it, and if you look at the two images below you will see the two front castor wheels are in slightly different positions (they have moved). The two wheels keep doing this motion where they turn inwards, and then outwards. this motion is done by both wheels and it takes about a second to do (inward to outward about a sec, and outward to inward about a sec). This motion never stops. I am hoping to eliminate this motion:

image description

image description

Here is a close up of the right wheel showing this motion (right wheel relative to robot):

image description

image description

Issue #2 - Contact with ground - I selected "contacts" from the "view" menu and the part of the wheel that makes contact with the ground changes many, many times a second. To show you what I mean I paused the simulation and took images as I pressed the "step" button on the bottom toolbar:

image description

image description

image description

image description

image description

image description

image description

Any suggestion on how my urdf has to change? what tags do I need to add to make the robot more stable?

My urdf is just shy of 800 lines, so I only included the items relevent to the right wheel (as the left wheel is identical).

reference image:

image description

URDF:

  <link name="right_castor_mount_link">
    <collision>
      <geometry>
        <box size="0.1145 0.1 0.0057"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0 0 0"/>
    </collision>
    <visual>
      <geometry>
        <box size="0.1145 0.1 0.0057"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <material name="black"/>
    </visual>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="0.25"/>
      <inertia ixx="0.000209010208333" ixy="0" ixz="0" iyy="0.000273807083333" iyz="0" izz="0.000273807083333"/>
    </inertial>
  </link>

  <joint name="base_to_right_castor_mount_joint" type="fixed">
    <parent link="base_link"/>
    <child link="right_castor_mount_link"/>
    <origin xyz="-0.09445 -0.344 -0.03265"/>
  </joint>


  <link name="right_castor_dummy_link">
    <collision>
      <geometry>
        <box size="0.02 0.02 0.02"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0 0 0"/>
    </collision>
    <visual>
      <geometry>
        <box size="0.02 0.02 0.02"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <material name="orange"/>
    </visual>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="0.25"/>
      <inertia ixx="1.66666666667e-05" ixy="0" ixz="0" iyy="1.66666666667e-05" iyz="0" izz="1.66666666667e-05"/>
    </inertial>
  </link>


  <joint name="right_castor_mount_to_right_castor_dummy_joint" type="continuous">
    <axis rpy="0 0 0" xyz="0 0 1"/>
    <parent link="right_castor_mount_link"/>
    <child link="right_castor_dummy_link"/>
    <origin xyz="0.0 0.0  -0.01"/>
    <dynamics damping="0.0" friction="1.0"/>
  </joint>


  <link name="right_castor_wheel_link">
    <collision>
      <geometry>
        <cylinder length="0.049" radius="0.07925"/>
      </geometry>
      <origin rpy="1.57079632679 0 0" xyz ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-02-15 18:00:48 -0500

TorontoRoboticsClub gravatar image

updated 2020-02-15 20:52:41 -0500

The issue was the absense of kp and kd tags. Those tags are mentioned here: http://gazebosim.org/tutorials/?tut=r... and values that worked for me were found here: http://answers.gazebosim.org/question...

Here is what I needed to add:

  <gazebo reference="right_castor_wheel_link">
      <kp>1000000.0</kp> <!--contact stiffness-->
      <kd>100.0</kd> <!--damping-->
  </gazebo>
edit flag offensive delete link more

Comments

As soon as I put these values (for all 4 wheels), the castor wheels stopped moving, and the robot stopped shifting the weight side to side. However the robot is now slowly rolling backwards. any advice?

TorontoRoboticsClub gravatar imageTorontoRoboticsClub ( 2020-02-15 20:55:28 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-02-15 14:00:07 -0500

Seen: 1,884 times

Last updated: Feb 15 '20