Parameters for a skid steering/simulated tracked robot (use of the fdir1 tag)
I´m trying to simulate a tracked robot by using multiple wheels and a modified skid steering plugin. It turned out that adjusting the friction parameters is quite tricky for this task.
There has been a lot of discussion on how to make a skid steering robot work in Gazebo in the past, but as far as I can see with no definitive conclusion/guide on how to do so. Some example discussions:
- how-do-i-set-up-mu-and-slip-for-a-skid-steer-robot - Gazebo does not work when adding adding slip parameters to by URDF´s gazebo friction parameters
- choosing-the-right-coefficients-for-gazebo-simulation
- rotation-error-in-gazebo-simulation - It appears after this discussion the fdir1 option has been added
I want to simulate a tracked vehicle using 5 skid steered wheels on each side of it. I have been able to tune the friction parameters a bit and have it working somewhat ok on a Gazebo empty world scenario. To illustrate, this is the robot system:
Visual representation on the left, internal representation (with collision geometry, five interecting wheels per side) on the right. The model is available on github in the hector_tracked_vehicles_description package ("test_fdir1_gazebo_answers" branch). It uses the diffdrive_plugin_multi_wheel available in the "add_diffdrive_multi_wheel" branch of hector_gazebo_plugins. It can be spawned into a gazebo world by running
roslaunch hector_tracked_vehicles_description spawn_jasmine_ugv_base.launch
The parameters I came up with so far for the wheel links are the following (they are set in tracked_wheel.urdf.xacro):
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<kp>1000000.0</kp>
<kd>10.0</kd>
<minDepth>0.001</minDepth>
<maxContacts>1</maxContacts>
Unfortunately, while working on flat ground, the vehicle is sliding a lot when on inclined/non-flat ground using these parameters. I tried using the fdir1 option, but this appears not to work in the way I understand all the documentation I found (This part of the ODE documentation is by far the best I could find). fdir1 is supposed to be given in the local coordinate frame of the colliding body (e.g. my wheel cylinders). My wheel cylinder is spinning around it´s y axis, so setting
<fdir1>0 1 0</fdir1>
appears to be the only setting that makes sense to me. Using this, it should be possible to set mu to adjust friction in the direction of the y axis and mu2 to adjust friction in the direction of the x axis of the robot (as fdir2 is calculated to be perpendicular to both fdir1 and the contact normal). Unfortunately, setting fdir1 as described (and keeping all other parameters the same) causes the robot to "wobble" while rotating and not stopping rotating when 0 rotational velocity is commanded. It appears this definitely does not work as I thought it should.
My related questions:
- Is there a way to get this to work properly using parameter tuning and proper use of fdir1? If so, all hints are appreciated. Also, a page on the gazebo wiki about these issues would probably be a good thing.
- Contact is always between two surfaces. So far I only looked at my wheel ...
I'll take a look at this when I have a chance. My first thoughts are to
View Contacts
to see if the contact points are jumping around, and also to increase the number of solver iterations to see if that has an effect.This seems to be related the question I just asked about omni-wheel modeling and fdir1/mu not working properly. (http://answers.gazebosim.org/question/5562/modeling-omni-wheels/). I'll link back to this question as well.
Converting the model to SDF and manually adding <slip1>0.0</slip1> <slip2>0.0</slip2> to ode element in collision->surface->friction might help, if they haven't been generated in the conversion process (in my case, they were not there). This might change how the model works, but I am not sure it will get the desired results.