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.
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>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="<a href=" http:="" playerstage.sourceforge.net="" gazebo="" xmlschema="" #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 ...
This question is on a related topic: http://answers.gazebosim.org/question/5476/parameters-for-a-skid-steeringsimulated-tracked/ ...seems like something is up (or at least misunderstood) with the <fdir1> tag.
Hi Gwen. Did you ever get this to work correctly with normal time settings? (you said you used 1/4th real time). Thanks
Hello, I'm having a similar problem, but as far as I've been able to understand, fdir1 is the vector that defines the direction of mu1, which is the "principal contact direction" (check it here: http://gazebosim.org/tutorials/?tut=ros_urdf#Links)
Have you tried checking the generated .sdf file? rosrun xacro xacro --inorder robot.xacro > robot.urdf gz sdf -p robot.urdf > robot.sdf Because for me the friction parameters are not generated at all. It looks like this: <friction> <ode/> </friction>
Hey Gwen can you share your whole omni wheel project somewhere? I would like to try and test it.