URDF to SDF conversion using gzsdf
Dear all,
As I'm currently trying to tune the dynamic behaviour of my robot modelled in a urdf(.xacro) file, I investigated the various urdf and gazebo tags available in order to see their effect to the simulation respectively.
This thread mainly deals with the conversion from urdf to sdf format using the gzsdf tool. So this thread is probably the first of several threads.
In the following I state my observations and would kindly ask someone to confirm them...or give explanations otherwise ;-)
I use the following setup: Trusty, Indigo, gazebo2_2.2.3-1~trusty_amd64
The robot I'm trying to tune is the Schunk lwa4p_extended. URDFs can be found here URDFs and launch files.
Other related links: gazebo-urdf-tutorial and sdf1.4.
I will number the questions so that answers can be referenced accordingly.
General questions
- The SDF version used in my setup (trusty, indigo, gazebo2) is SDF1.4?
- Where is SDF1.5 used? With gazebo3? Or gazebo4?
You can convert a urdf.xacro file to sdf uding the following commands
rosrun xacro xacro.py robotlwa4pextended.urdf.xacro > robotlwa4pextended.urdf
gzsdf print robotlwa4pextended.urdf > robotlwa4pextended.sdfWhen spawning a robot in gazebo using
gazebo_ros/spawn_model
the samegzsdf
is used to convert the parameter/robot_description
to sdf format which is then used in gazebo?Within a urdf gazebo tag (referencing a link or joint), I can use all tags listed in the gazebo-urdf-tutorial? I.e.:
- material, gravity, dampingFactor, maxVel, minDepth, mu1, mu2, fdir1, kp, kd, selfCollide, maxContacts, laserRetro for links
- kp, kd, stopCfm, stopErp, provideFeedback, cfmDamping, fudgeFactor for joints
Within a urdf gazebo tag (referencing a link or joint), I can also use sdf tags from sdf1.4 directly?
Tag specific questions
gravity
,selfCollide
andself_collide
(gazebo tag for links)
Adding one of the tags above for a link, an additional tag is added to the resulting sdf file, i.e. there are then twogravity
tags for the same link in the sdf file where the first is always set to true (1) and the second sdf tag holds the value set in the urdf. I assume that when gazebo parses the sdf file, it always finds the first tag using their value, thus always neglecting what has been set in the urdf.kp
,kd
,mu1
,mu2
,maxVel
,minDepth
,fdir1
,maxContacts
,laserRetro
,dampingFactor
(gazebo tag for links)
All those tags seem to be converted to sdf correctly.damping
andfriction
(urdf tag for joints)
friction
is currently ignored, i.e. it's value is not even converted into the sdf file?Empty gazebo tag referencing a joint
<gazebo reference="${name}_1_joint"> </gazebo> is converted into <physics> <ode> <limit> <cfm>0</cfm> <erp>0.2</erp> </limit> </ode> </physics>
stopCfm
,stopErp
(gazebo tag for joint)<gazebo reference="${name}_1_joint"> <stopCfm>0.3</stopCfm> <stopErp>0.4</stopErp> </gazebo> is converted into <physics> <ode> <limit> <cfm>0.3</cfm> <erp>0.4</erp> </limit> </ode> </physics>
cfmDamping
,implicitSpringDamper
,cfm_damping
,implicit_spring_damper
(gazebo tag ...
Note that in newer versions of Gazebo, the tool used to convert from URDF to SDF has changed, and it is now `gz sdf -p my_urdf.urdf > my_sdf.sdf`