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>