ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Wheels not revolving in place in gazebo

asked 2020-12-28 13:12:23 -0500

arjunchatterg gravatar image

updated 2020-12-30 15:58:03 -0500

I have imported a 2 wheel differential drive robot from fusion-360 to urdf to simulate it in the gazebo. The import was successful but when I launched teleop, the wheel started behaving abnormally and the bot ultimately toppled.

This is the link to GitHub repo of my work which I'm working on. And here's the video of the issue.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-12-29 14:37:52 -0500

updated 2020-12-30 01:46:57 -0500

Your visual and collision origin is not same thing and also visual origin is not looks like true. Firstly you have to change your urdf wheel collision part with cylinder. Secondly you can try without stl model visual part like turtlebot3. After this changes if your simulation works true and wheels turn fine you can change visual part easily.

Turtlebot3 wheel URDF example

 <link name="wheel_left_link">
        <visual>
          <origin xyz="0 0 0" rpy="1.57 0 0"/>
          <geometry>
            <mesh filename="package://turtlebot3_description/meshes/wheels/left_tire.stl" scale="0.001 0.001 0.001"/>
          </geometry>
          <material name="dark"/>
        </visual>
        <collision>
          <origin xyz="0 0 0" rpy="0 0 0"/>
          <geometry>
            <cylinder length="0.018" radius="0.033"/>
          </geometry>
        </collision>
        <inertial>
          <origin xyz="0 0 0" />
          <mass value="2.8498940e-02" />
          <inertia ixx="1.1175580e-05" ixy="-4.2369783e-11" ixz="-5.9381719e-09"
                   iyy="1.1192413e-05" iyz="-1.4400107e-11"
                   izz="2.0712558e-05" />
          </inertial>
      </link>

Another example

    <xacro:macro name="wheel" params="prefix reflect">
            <link name="${prefix}_wheel_link">
              <visual>
            <material name="darkgray"/>
                <origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
                <geometry>
                  <cylinder radius="${wheel_radius}" length="0.02"/>
                </geometry>
              </visual>
              <collision>
                <origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
                <geometry>
                  <cylinder radius="${wheel_radius}" length="0.02"/>
                </geometry>
              </collision>
              <xacro:cylinder_inertia m="10" r="${wheel_radius}" h="0.02"/>
            </link>
            <joint name="${prefix}_wheel_joint" type="continuous">
              <axis xyz="0 1 0" rpy="0 0 0" />
              <parent link="base_link"/>
              <child link="${prefix}_wheel_link"/>
              <origin xyz="${wheel_joint_offset} ${((base_width/2)+base_wheel_gap)*reflect} -0.06" rpy="0 0 0"/>
            </joint>
          </xacro:macro>

  <xacro:wheel prefix="left" reflect="1"/>
  <xacro:wheel prefix="right" reflect="-1"/>
edit flag offensive delete link more

Comments

Hi. Thank you for your response. Being a beginner, I'm facing a bit issue in understanding your comment.

Is this what you mean to say?

<link name="wheel_right_1">
  <inertial>
    <origin rpy="0 0 0" xyz="2.6219412913944283e-15 0.14694203191398253 0.050000000000012125"/>
    <mass value="1.0207980214073948"/>
    <inertia ixx="0.000884" ixy="0.0" ixz="0.0" iyy="0.00167" iyz="0.0" izz="0.000884"/>
  </inertial>
  <!-- <visual>
    <origin rpy="0 0 0" xyz="-0.0 0.015 -0.0"/>
    <geometry>
      <mesh filename="package://greybot_description/meshes/wheel_right_1.stl" scale="0.001 0.001 0.001"/>
    </geometry>
    <material name="silver"/>
  </visual> -->
  <collision>
    <origin rpy="0 0 0" xyz="-0.0 0.015 -0.0"/>
    <geometry>
      <!-- <mesh filename="package://greybot_description/meshes/wheel_right_1.stl" scale="0.001 0.001 0.001"/> -->
      <cylinder length="0.018" radius="0.1 ...
(more)
arjunchatterg gravatar image arjunchatterg  ( 2020-12-30 01:38:14 -0500 )edit

I added one more example. I mean firstly you can create your urdf without stl model file only geometrical shapes. The center of the wheel does not look right.

bekirbostanci gravatar image bekirbostanci  ( 2020-12-30 01:53:03 -0500 )edit

I am still struggling with no success. Here's the updated link and the fusion-360 design link, could I request you to solve it?

arjunchatterg gravatar image arjunchatterg  ( 2020-12-30 15:51:37 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-12-28 13:12:23 -0500

Seen: 716 times

Last updated: Dec 30 '20