Model slips on ground and cannot acheive given velocity

asked 2020-04-07 00:33:52 -0500

Withered_Shadow gravatar image

Hi, Im trying to implement a program for multi robot obstacle avoidance. Right now I have a code which outputs a desired velocity. However, my robot is never able to achieve the given velocity. Also the bot continues moving even after I stop the program. I have attached the URDF model below for the robot (has omni wheels with 10 rollers).

<?xml version="1.0"?>
  <robot xmlns:xacro="http://www.ros.org/wiki/xacro"
         xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
         xmlns:interface="http://ros.org/wiki/xacro"
         xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" name="ballbot">

<link name="dummy">
   </link>

 <xacro:macro name="omni" params="x y z roll pit yaw pos">
  <link name="wheel${pos}">
    <collision>
    <origin xyz="0 0 0" rpy="${roll} ${pit} ${yaw}"/>
      <geometry>
        <mesh filename="package://omni_bot/src/Wheel2_Double_ohneRaeder.stl" scale=".0021 .0021 .0021"/>
      </geometry>
      <surface>
        <friction>
          <ode>
            <mu>0.6</mu>
            <mu2>0.6</mu2>
            <slip1>0.0</slip1>
            <slip2>0.0</slip2>
            <fdir1>1 0 0</fdir1>
          </ode>
        </friction>
      </surface>

    </collision>
    <visual>
    <origin xyz="0 0 0" rpy="${roll} ${pit} ${yaw}"/>
      <geometry>
        <mesh filename="package://omni_bot/src/Wheel2_Double_ohneRaeder.stl" scale=".0021 .0021 .0021"/>
      </geometry>
    </visual>
    <inertial>
      <origin xyz="0 0 0" rpy="${roll} ${pit} ${yaw}"/>
      <mass value = "2.5"/>
      <inertia ixx="0.00108333333333" ixy="0" ixz="0" iyy="0.00108333333333" iyz="0" izz="0.002"/>
    </inertial>
    <!-- <gravity> 1 </gravity>
    <selfCollide>0</selfCollide> -->
  </link>


  <link name="roller1${pos}">
    <collision >
      <origin xyz="0 0 0" rpy="0 0 1.57079"/>
      <geometry>
        <mesh filename="package://omni_bot/src/Wheel2_wheel_rightOrient.stl" scale=".0021 .0021 .0021"/>
      </geometry>
      <surface>
        <friction>
          <ode>
            <mu>0.6</mu>
            <mu2>0.6</mu2>
            <slip1>0.0</slip1>
            <slip2>0.0</slip2>
            <fdir1>1 0 0</fdir1>
          </ode>
        </friction>
      </surface>

    </collision>
    <visual >
      <origin xyz="0 0 0" rpy="0 0 1.57079"/>
      <geometry>
        <mesh filename="package://omni_bot/src/Wheel2_wheel_rightOrient.stl" scale=".0021 .0021 .0021"/>
      </geometry>
    </visual>
    <inertial>
      <origin xyz="0 0 0" rpy="0 0 1.57079"/>
      <mass value = "0.1"/>
      <inertia ixx="0.00000847" ixy ="0" ixz="0" iyy="0.00000847" iyz="0.0" izz="0.00000847"/>
    </inertial>

<!-- <gravity> 1 </gravity>
<selfCollide>0</selfCollide> -->
  </link>
  <joint name="1${pos}" type="continuous">
    <parent link="wheel${pos}"/>
    <child link="roller1${pos}"/>
    <origin xyz="${0.222*(-(0)*sin(yaw)+((0.05-0.28)*sin(pit)+(0.137)*cos(pit))*cos(yaw))} ${0.222*(((0)*cos(yaw))+((0.05-0.28)*sin(pit)+(0.137)*cos(pit))*sin(yaw))} ${0.222*((0.05-0.28)*cos(pit)+0.28-(0.137)*sin(pit)-0.28)}" rpy="${roll} ${pit} ${yaw}"/>
    <axis xyz="0 1 0"/>
       <!-- <dynamics>
        <damping>0.7</damping>
        <friction>0.4</friction>
       </dynamics> -->
  </joint>

  <link name="roller2${pos}">
    <collision >
      <origin xyz="0 0 0" rpy="0 -1.25664 1.57079"/>
      <geometry>
        <mesh filename="package://omni_bot/src/Wheel2_wheel_rightOrient.stl" scale=".0021 .0021 .0021"/>
      </geometry>
      <surface>
        <friction>
          <ode>
            <mu>0.6</mu>
            <mu2>0.6</mu2>
            <slip1>0.0</slip1>
            <slip2>0.0</slip2>
            <fdir1>1 0 0</fdir1>
          </ode>
        </friction>
      </surface>

    </collision>
    <visual >
      <origin xyz="0 0 ...
(more)
edit retag flag offensive close merge delete