Gazebo | Ignition | Community
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Modeling Omni Wheels

I would like to model an omni wheel. Ideally, I would like to do this using non-uniform friction properties (see below). However, it seems like the contact algorithm is giving preference to the friction properties of the static ground plane over the wheels. That is, I can get the wheels to slip if I set <mu> and <mu2> to 0 (or <friction> and <friction2> for Bullet) for the ground plane, BUT, setting the same properties for the wheels does not result in slipping. With any luck I have a simple error in my urdf. There are a few other threads regarding omni wheels that are a few years old, but I haven't found a satisfactory answer--I have seen this method of friction modification suggested, but no examples of successful implementation.

As a side note, I also tried a physical omni wheel model (w/ a whole bunch of spherical collisions around the edge attached by continuous joints) and had stability issues for most reasonable time steps (as expected).

omni-wheel macro: z-axis is axial directino.

<link name="${wheel_name}"> <inertial> <mass value="${wheel_mass}"/> <origin xyz="0 0 0" rpy="0 0 0"/> <inertia ixx="${ixx}" iyy="${iyy}" izz="${izz}" ixy="${ixy}" ixz="${ixz}" iyz="${iyz}"/> </inertial> <visual name="${wheel_name}_vis"> <origin xyz="0 0 0.05" rpy="0 0 0"/> <geometry name="${wheel_name}_geom"> <mesh filename="${wheel_visual}"/> </geometry> </visual> <collision name="${wheel_name}_col"> <origin xyz="0 0.0 0" rpy="0 0 0"/> <geometry name="${wheel_name}_geom"> <cylinder length="0.025" radius="${wheel_radius}"/> </geometry> <surface> <friction> <ode> <mu>0</mu> <mu2>1</mu2> <fdir1>0 0 1</fdir1> </ode> <bullet> <friction>0</friction> <friction2>1</friction2> <fdir1>0 0 1</fdir1> </bullet> </friction> </surface> </collision> </link>

click to hide/show revision 2
formatted code snippet

Modeling Omni Wheels

I would like to model an omni wheel. Ideally, I would like to do this using non-uniform friction properties (see below). However, it seems like the contact algorithm is giving preference to the friction properties of the static ground plane over the wheels. That is, I can get the wheels to slip if I set <mu> and <mu2> to 0 (or <friction> and <friction2> for Bullet) for the ground plane, BUT, setting the same properties for the wheels does not result in slipping. With any luck I have a simple error in my urdf. There are a few other threads regarding omni wheels that are a few years old, but I haven't found a satisfactory answer--I have seen this method of friction modification suggested, but no examples of successful implementation.

As a side note, I also tried a physical omni wheel model (w/ a whole bunch of spherical collisions around the edge attached by continuous joints) and had stability issues for most reasonable time steps (as expected).

omni-wheel macro: z-axis is axial directino.

<link name="${wheel_name}">
     <inertial>
         <mass value="${wheel_mass}"/>
         <origin xyz="0 0 0" rpy="0 0 0"/>
         <inertia ixx="${ixx}" iyy="${iyy}" izz="${izz}" ixy="${ixy}" ixz="${ixz}" iyz="${iyz}"/>
     </inertial>
     <visual name="${wheel_name}_vis">
         <origin xyz="0 0 0.05" rpy="0 0 0"/>
         <geometry name="${wheel_name}_geom">
             <!-- <cylinder length="0.025" radius="${wheel_radius}"/> -->
            <mesh filename="${wheel_visual}"/>
         </geometry>
     </visual>
     <collision name="${wheel_name}_col">
          <origin xyz="0 0.0 0" rpy="0 0 0"/>
          <geometry name="${wheel_name}_geom">
             <cylinder length="0.025" radius="${wheel_radius}"/>
             <!-- <sphere radius="${wheel_radius}"/> -->
         </geometry>
          <surface>
             <friction>
                 <ode>
                     <mu>0</mu>
                     <mu2>1</mu2>
                     <fdir1>0 0 1</fdir1>
                 </ode>
                 <bullet>
                     <friction>0</friction>
                     <friction2>1</friction2>
                     <fdir1>0 0 1</fdir1>
                 </bullet>
             </friction>
          </surface>
     </collision>
    </link> 

</link>
click to hide/show revision 3
Fixed error in urdf snippet, but fdir1 still not being used properly by physics engine (apparently)

Modeling Omni Wheels

I would like to model an omni wheel. Ideally, I would like to do this using non-uniform friction properties (see below). However, it seems like the contact algorithm is giving preference not properly accounting for the fdir1 parameter, as setting either <mu1> or <mu2> to zero causes the friction properties of the static ground plane over the wheels. That is, I can get the wheels wheel to slip if I set <mu> and <mu2> to 0 (or <friction> and <friction2> for Bullet) for the ground plane, BUT, setting the same properties for the wheels does not result in slipping. With any luck I have a simple error in my urdf. when rotating. There are a few other threads regarding omni wheels that are a few years old, but I haven't found a satisfactory answer--I have seen this method of friction modification suggested, but no examples of successful implementation.

As a side note, I also tried a physical omni wheel model (w/ a whole bunch of spherical collisions around the edge attached by continuous joints) and had stability issues for most reasonable time steps (as expected).

omni-wheel macro: z-axis is axial directino.direction.

<link name="${wheel_name}">
    <inertial>
        <mass value="${wheel_mass}"/>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <inertia ixx="${ixx}" iyy="${iyy}" izz="${izz}" ixy="${ixy}" ixz="${ixz}" iyz="${iyz}"/>
    </inertial>
    <visual name="${wheel_name}_vis">
        <origin xyz="0 0 0.05" rpy="0 0 0"/>
        <geometry name="${wheel_name}_geom">
            <!-- <cylinder length="0.025" radius="${wheel_radius}"/> -->
            <mesh filename="${wheel_visual}"/>
        </geometry>
    </visual>
    <collision name="${wheel_name}_col">
         <origin xyz="0 0.0 0" rpy="0 0 0"/>
         <geometry name="${wheel_name}_geom">
            <cylinder length="0.025" radius="${wheel_radius}"/>
            <!-- <sphere radius="${wheel_radius}"/> -->
         </geometry>
         <surface>
            <friction>
                <ode>
                    <mu>0</mu>
                    <mu2>1</mu2>
                </collision>
</link> 
<gazebo reference="${wheel_name}">
    <mu1>0</mu1>
    <mu2>10000</mu2>
    <fdir1>0 0 1</fdir1>
                </ode>
                <bullet>
                    <friction>0</friction>
                    <friction2>1</friction2>
                    <fdir1>0 0 1</fdir1>
                </bullet>
            </friction>
         </surface>
    </collision>
</link>
</gazebo>
click to hide/show revision 4
Attaching a quasi-functional physical omni wheel model as a stand in until the friction issue is fixed

Modeling Omni Wheels

I would like to model an omni wheel. Ideally, I would like to do this using non-uniform friction properties (see below). However, it seems like the contact algorithm is not properly accounting for the fdir1 parameter, as setting either <mu1> or <mu2> to zero causes the wheel to slip when rotating. There are a few other threads regarding omni wheels that are a few years old, but I haven't found a satisfactory answer--I have seen this method of friction modification suggested, but no examples of successful implementation.

As a side note, I also tried a physical omni wheel model (w/ a whole bunch of spherical collisions around the edge attached by continuous joints) and had stability issues for most reasonable time steps (as expected).

omni-wheel macro: z-axis is axial direction.

<link name="${wheel_name}">
    <inertial>
        <mass value="${wheel_mass}"/>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <inertia ixx="${ixx}" iyy="${iyy}" izz="${izz}" ixy="${ixy}" ixz="${ixz}" iyz="${iyz}"/>
    </inertial>
    <visual name="${wheel_name}_vis">
        <origin xyz="0 0 0.05" rpy="0 0 0"/>
        <geometry name="${wheel_name}_geom">
            <!-- <cylinder length="0.025" radius="${wheel_radius}"/> -->
            <mesh filename="${wheel_visual}"/>
        </geometry>
    </visual>
    <collision name="${wheel_name}_col">
         <origin xyz="0 0.0 0" rpy="0 0 0"/>
         <geometry name="${wheel_name}_geom">
            <cylinder length="0.025" radius="${wheel_radius}"/>
            <!-- <sphere radius="${wheel_radius}"/> -->
         </geometry>
    </collision>
</link> 
<gazebo reference="${wheel_name}">
    <mu1>0</mu1>
    <mu2>10000</mu2>
<mu2>1</mu2>
    <fdir1>0 0 1</fdir1>
</gazebo>

UPDATE : I actually did manage to get a physical model to "work" which is stable at 1/4th real time. However, the collision model means that the wheel looks like a ball, so any vehicle which uses it won't be able to get too close to any other object in the work (which is acceptable for my purposes right now). My robot uses three of these wheels and the following ODE parameters in the world:

  <ode>
    <solver>
      <type>quick</type>
      <iters>200</iters>
      <sor>1.2</sor>
    </solver>
    <constraints>
      <cfm>0.0</cfm>
      <erp>0.2</erp>
      <contact_max_correcting_vel>0.01</contact_max_correcting_vel>
      <contact_surface_layer>0.0001</contact_surface_layer>
    </constraints>
  </ode>
  <real_time_update_rate>2000</real_time_update_rate>
  <max_step_size>0.0005</max_step_size>

Here is the omni wheel xacro (please excuse the comments left in for debugging):

<?xml version='1.0'?>

<robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">

<property name="M_PI" value="3.1415926535897931"/> <property name="M_PI2" value="1.57079632679"/>

<xacro:macro name="subwheel" params="wheel_name wheel_radius subwheel_number n_subwheels cos_2pi_n_over_N sin_2pi_n_over_N cos_pi_over_N sin_pi_over_N subwheel_mass subwheel_joint_type">

<joint name="${wheel_name}_subwheel_${subwheel_number}_j" type="${subwheel_joint_type}">
    <origin xyz="${0.05*wheel_radius * cos_pi_over_N * cos_2pi_n_over_N} ${0.05*wheel_radius * cos_pi_over_N * sin_2pi_n_over_N} 0" rpy="0 0 ${2*M_PI*subwheel_number/n_subwheels}"/>
    <!-- <axis xyz="${-sin_2pi_n_over_N} ${cos_2pi_n_over_N} 0"/> -->
    <axis xyz="0 1 0"/>
    <parent link="${wheel_name}"/>
    <child link="${wheel_name}_subwheel_${subwheel_number}_l"/>
</joint>    

<!-- <gazebo reference="${wheel_name}_subwheel_${subwheel_number}_j">
    <dynamics>
        <damping>10</damping>
        <friction>1</friction>
    </dynamics>
</gazebo> -->

<link name="${wheel_name}_subwheel_${subwheel_number}_l">
    <inertial>
        <mass value="${subwheel_mass}"/>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <inertia ixx="${2*subwheel_mass*(wheel_radius*wheel_radius*sin_pi_over_N*sin_pi_over_N)/5}" 
                 iyy="${2*subwheel_mass*(wheel_radius*wheel_radius*sin_pi_over_N*sin_pi_over_N)/5}"
                 izz="${2*subwheel_mass*(wheel_radius*wheel_radius*sin_pi_over_N*sin_pi_over_N)/5}"
                 ixy="0"
                 ixz="0"
                 iyz="0"/>
    </inertial>
    <!-- <visual name="${wheel_name}_subwheel_${subwheel_number}_vis">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry name="${wheel_name}_subwheel_${subwheel_number}_geom">
            <sphere radius="${wheel_radius}"/>
        </geometry>
    </visual> -->
    <collision name="${wheel_name}_subwheel_${subwheel_number}_col">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry name="${wheel_name}_subwheel_${subwheel_number}_geom">
            <sphere radius="${wheel_radius}"/>
        </geometry>
    </collision>
</link>

</xacro:macro>

<xacro:macro name="omni_wheel_18subs" params="wheel_name wheel_radius wheel_mass wheel_visual ixx iyy izz ixy ixz iyz subwheel_mass subwheel_joint_type color"> <link name="${wheel_name}"> <inertial> <mass value="${wheel_mass}"/> <origin xyz="0 0 0" rpy="0 0 0"/> <inertia ixx="${ixx}" iyy="${iyy}" izz="${izz}" ixy="${ixy}" ixz="${ixz}" iyz="${iyz}"/> </inertial> <visual name="${wheel_name}_vis"> <origin xyz="0 0 0.05" rpy="0 0 0"/> <geometry name="${wheel_name}_geom"> <mesh filename="${wheel_visual}"/> </geometry> </visual> </link> <gazebo reference="${wheel_name}"> <material>Gazebo/${color}</material> </gazebo>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="0" n_subwheels="18" cos_2pi_n_over_N="1" sin_2pi_n_over_N="0" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="1" n_subwheels="18" cos_2pi_n_over_N="0.939692620785908" sin_2pi_n_over_N="0.342020143325669" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="2" n_subwheels="18" cos_2pi_n_over_N="0.766044443118978" sin_2pi_n_over_N="0.642787609686539" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="3" n_subwheels="18" cos_2pi_n_over_N="0.5" sin_2pi_n_over_N="0.866025403784439" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="4" n_subwheels="18" cos_2pi_n_over_N="0.17364817766693" sin_2pi_n_over_N="0.984807753012208" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="5" n_subwheels="18" cos_2pi_n_over_N="-0.17364817766693" sin_2pi_n_over_N="0.984807753012208" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="6" n_subwheels="18" cos_2pi_n_over_N="-0.5" sin_2pi_n_over_N="0.866025403784439" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="7" n_subwheels="18" cos_2pi_n_over_N="-0.766044443118978" sin_2pi_n_over_N="0.64278760968654" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="8" n_subwheels="18" cos_2pi_n_over_N="-0.939692620785908" sin_2pi_n_over_N="0.342020143325669" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="9" n_subwheels="18" cos_2pi_n_over_N="-1" sin_2pi_n_over_N="0.0" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="10" n_subwheels="18" cos_2pi_n_over_N="-0.939692620785908" sin_2pi_n_over_N="-0.342020143325669" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="11" n_subwheels="18" cos_2pi_n_over_N="-0.766044443118978" sin_2pi_n_over_N="-0.642787609686539" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="12" n_subwheels="18" cos_2pi_n_over_N="-0.5" sin_2pi_n_over_N="-0.866025403784438" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="13" n_subwheels="18" cos_2pi_n_over_N="-0.17364817766693" sin_2pi_n_over_N="-0.984807753012208" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="14" n_subwheels="18" cos_2pi_n_over_N="0.17364817766693" sin_2pi_n_over_N="-0.984807753012208" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="15" n_subwheels="18" cos_2pi_n_over_N="0.5" sin_2pi_n_over_N="-0.866025403784439" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="16" n_subwheels="18" cos_2pi_n_over_N="0.766044443118978" sin_2pi_n_over_N="-0.64278760968654" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

<xacro:subwheel wheel_name="${wheel_name}" wheel_radius="${wheel_radius}" subwheel_number="17" n_subwheels="18" cos_2pi_n_over_N="0.939692620785908" sin_2pi_n_over_N="-0.342020143325669" cos_pi_over_N="0.984807753012208" sin_pi_over_N="0.17364817766693" subwheel_mass="${subwheel_mass}" subwheel_joint_type="${subwheel_joint_type}"/>

</xacro:macro>

</robot>

Also, my ground plane is modified with the following surface parameters :

             <surface>
                <friction>
                    <ode>
                        <mu>0.8</mu>
                    </ode>
                </friction>
                <bounce>
                    <restitution_coefficient>0.0</restitution_coefficient>
                </bounce>
                <contact>
                    <ode>
                        <kp>50000</kp>
                        <kd>5000</kd>
                        <max_vel>0</max_vel>
                    </ode>
                </contact>
            </surface>