Gazebo | Ignition | Community
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Using SDF tags in URDF (gazebo extension) directly?

This questions is related to the previous thread: urdf-to-sdf-conversion [1].

Now, I'm reporting my observations when trying to use SDF tags from sdf1.4 in the URDF directly.

As mentioned in [1], it should be possible to use SDF within the gazebo tags referencing a link or joint within the URDF directly.

SDF tags for links

For setting most of the SDF tags relevant for links, URDF does not need the gazebo extensions, i.e. pose, ├Čnertial, visual and collision related tags are correctly set up using urdf-xml-link.

  1. gravity and self_collide
    It's the same result as mentioned in this issue

  2. kinematic
    It is converted to sdf. But seems to have no effect according to this thread

  3. velocity_decay
    The following can be used to set velocity_decay of a link.
    With this, it's possible to set different values for linear and angular (in contrast to using the gazebo tag dampingFactor).

    <gazebo reference="${name}_base_link">
      <velocity_decay>
        <linear>0.2</linear>
        <angular>0.4</angular>
      </velocity_decay>
    </gazebo>
    

SDF tags for joints

Similar to the above mentioned, tags that can correctly be set up using urdf-xml-joint are not considered here.

  1. damping and friction (dynamics)
    damping of an axis can only be set using the URDF tag dynmaics -> damping.
    All the following variants are not converted into the SDF file:

    <gazebo reference="${name}_1_joint">
      <axis>
        <dynamics>
          <damping>0.7</damping>
          <friction>0.7</friction>
        </dynamics>
      </axis>
      <dynamics>
        <damping>0.6</damping>
        <friction>0.6</friction>
      </dynamics>
      <damping>0.5</damping>
      <friction>0.5</friction> 
    </gazebo>
    

    friction cannot be set from anywhere as it is currently (not yet) supported (see PullRequest)

  2. physics for ode (ode)
    Both following variants are not converted into the SDF file:

    <gazebo reference="${name}_1_joint">
    
      <provide_feedback>true</provide_feedback>
      <cfm_damping>true</cfm_damping>
      <fudge_factor>80</fudge_factor>
      <cfm>81</cfm>
      <erp>82</erp>
      <bounce>83</bounce>
      <max_force>84</max_force>
      <velocity>85</velocity>
      <limit>
        <cfm>86</cfm>
        <erp>87</erp>
      </limit>
      <suspension>
        <cfm>88</cfm>
        <erp>89</erp>
      </suspension>
    
      <physics>
        <ode>
          <provide_feedback>true</provide_feedback>
          <cfm_damping>true</cfm_damping>
          <fudge_factor>90</fudge_factor>
          <cfm>91</cfm>
          <erp>92</erp>
          <bounce>93</bounce>
          <max_force>94</max_force>
          <velocity>95</velocity>
          <limit>
            <cfm>96</cfm>
            <erp>97</erp>
          </limit>
          <suspension>
            <cfm>98</cfm>
            <erp>99</erp>
          </suspension>
        </ode>
      </physics>
    
    </gazebo>
    

Thus, it seems that using SDF tags directly within a URDF file is not supported - at least the way I tried to use them. In case I used them in the wrong way, please let me know! I'd be happy to test again then...

The only tags that are converted into the SDF file are gravity, self_collide (however, not considered due to issue), kinematic (however, see thread) and velocity_decay.