Gazebo | Ignition | Community
Ask Your Question
1

slip1, slip2 in URDF

asked 2013-06-26 02:12:36 -0500

ZdenekM gravatar image

Hi all,

I'm working on URDF model of skid steering robot (Pioneer 3AT). There is new plugin for controlling this type of robot (see gazebo_plugins package) so, I can command robot from ROS and it moves. But I have problems with rotational movements - robot can't rotate. If I define wheels (collision geometry) as very thin cylinders and apply high torque it "somehow" rotates... If collision geometry is defined using mesh it's better but, robot jumps a bit.

The question is - how can I set slip1/slip2 (as setting this is recommended here) using URDF? As far as I know, URDF is translated into SDF so, I guess, it should be somehow possible. Thanks for hints in advance.

I'm using Gazebo 1.8 and gazeborospkgs for ROS integration.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2013-06-27 18:12:17 -0500

nkoenig gravatar image

URDF has no concept of friction, so you'll have to insert SDF (which is currently specified using the <gazebo> extension).

Something like

  <gazebo reference="r_foot">
    <!-- kp and kd for rubber -->
    <kp>1000000.0</kp>
    <kd>100.0</kd>
    <mu1>1.5</mu1>
    <mu2>1.5</mu2>
    <fdir1>1 0 0</fdir1>
    <maxVel>1.0</maxVel>
    <minDepth>0.00</minDepth>
  </gazebo>
edit flag offensive delete link more

Comments

This is documented [here](http://gazebosim.org/wiki/Tutorials/1.9/Using_A_URDF_In_Gazebo#.3Cgazebo.3E_Elements_For_Links)

davetcoleman gravatar imagedavetcoleman ( 2013-06-27 19:09:45 -0500 )edit

Question Tools

Stats

Asked: 2013-06-26 02:12:36 -0500

Seen: 5,246 times

Last updated: Jun 27 '13