friction coefficients not translating from URDF to SDF with <gazebo> tags

asked 2020-06-19 15:15:16 -0500

JoshuaElliott gravatar image

updated 2020-12-07 11:00:09 -0500

Edit: Converting everything to Xacro has solved the problem for unknown reasons

Ubuntu 16, Kinetic, Gazebo 7

I have been trying to modify mu1, mu2, kd, kp from their default values by inserting the <gazebo> tags into the URDF for my robot. It seems that no matter how I insert them into the URDF, it fails to translate to the SDF that Gazebo then actually works with. If I launch the URDF based model into Gazebo, save it, modify the SDF, then insert it back into Gazebo then things work as expected and the modified values work.

I am very new to ROS and Gazebo so I imagine there is some basic flaw in my understanding and I welcome any suggestions.

The <gazebo> tag is at the end of the file below and references the link "back_left", which is one of the robot's wheels.

I have gone through this tutorial and others without any luck

<?xml version='1.0'?>
<robot name="dd_robot">
 <link name="base_link">
  <inertial>
   <mass value="65"/>
   <origin rpy="1.560795  0       0" xyz="-0.39318  0.62378 0.1"/>
   <inertia ixx="0.166667" ixy="0" ixz="0" iyy="0.166667" iyz="0" izz="0.166667"/>
  </inertial>
  <collision name="collision">
   <origin rpy="1.560795  0       0" xyz="-0.39318  0.62378 -0.03459"/>
   <geometry>
    <mesh filename="package://ros_robotics/meshes/body.STL" scale="1.0 1.0 1.0"/>
   </geometry>
  </collision>
  <visual name="visual">
   <origin rpy="1.560795  0       0" xyz="-0.39318  0.62378 -0.03459"/>
   <geometry>
    <mesh filename="package://ros_robotics/meshes/body.STL" scale="1 1 1"/>
   </geometry>
   <material name="silver">
    <color rgba="0.75 0.75 0.75 1"/>
   </material>
  </visual>
 </link>
 <joint name="joint_pivot" type="revolute">
  <parent link="base_link"/>
  <child link="front_axle"/>
  <origin rpy="0    0   -1.57" xyz="-0.39318  0.07711  0.00165"/>
  <axis xyz="0  0  1"/>
  <limit effort="-1" lower="-0.157" upper="0.157" velocity="-1"/>
 </joint>
 <joint name="joint_back_left" type="continuous">
  <parent link="base_link"/>
  <child link="back_left"/>
  <origin rpy="0  0  0" xyz="0.18208  1.13494 -0.09617"/>
  <axis xyz="1  0  0"/>
  <limit effort="90" velocity="20"/>
 </joint>
 <joint name="joint_back_right" type="continuous">
  <parent link="base_link"/>
  <child link="back_right"/>
  <origin rpy="0  0  0" xyz="-0.96759  1.13494 -0.09617"/>
  <axis xyz="1  0  0"/>
  <limit effort="90" velocity="20"/>
 </joint>
 <joint name="joint_front_left" type="continuous">
  <parent link="front_axle"/>
  <child link="front_left"/>
  <origin rpy="0    0    1.57" xyz="0.00186  0.57526 -0.09782"/>
  <axis xyz="1  0  0"/>
  <limit effort="90" velocity="20"/>
 </joint>
 <joint name="joint_front_right" type="continuous">
  <parent link="front_axle"/>
  <child link="front_right"/>
  <origin rpy="-2.36140000e+00  -3.00000000e-05   1.57004000e+00" xyz="0.00094 -0.57441 ...
(more)
edit retag flag offensive close merge delete

Comments

Hi

First of all I recommend you to update tot the last stable version of Gazebo 7, that is Gazebo 7.14 I think.

Apart from that, have you tried to place the parameters explicitly like in the SDF? E.g.:

<gazebo reference="back_left">
 <collision>
  <surface>
   <contact>
    <ode>
     <kp>1.0</kp>
     <kd>0.01</kd>
     <max_vel>0.0</max_vel>
     <min_depth>0.001</min_depth>
    </ode>
   </contact>
   <friction>
    <ode>
     <mu>0.9</mu> 
     <mu2>0.9</mu2>
    </ode>
   </friction>
  </surface>
 </collision>
</gazebo>
Weasfas gravatar image Weasfas  ( 2020-06-20 03:35:38 -0500 )edit

I have updated to "gazebo7 7.16.0-1~xenial" per your recommendation but it didn't change anything so far.

When I copy your code snippet (thank you for that) into the urdf it yields no change. I tested with the <gazebo> tag (and children) both inside and outside the <robot> tag, based on errors it threw it seems like I definitely want it within the <robot> tag (which is where I previously had it).

I'm starting to wonder if I should instead be defining the robot directly as an SDF, but I'm not sure how that would mess up the ROS integration which is the whole purpose of what I'm working on.

I tested instead defining the friction of the surface I'm interacting with by copying some of the code from this tutorial into my own world file and that worked, so this is at ...(more)

JoshuaElliott gravatar image JoshuaElliott  ( 2020-06-20 08:38:07 -0500 )edit

But how are you sure that the contact tags are not being passed to the final SDF?

The flow of information usually is Xacro > URDF > SDF, since you have only a URDF file you can just try to generate the SDF file and check that indeed the tags are not being translated properly. E.g.:

gz-7.16.0 sdf -p model.urdf > model.sdf

Besides that, generally when you convert Xacro to URDF the parser usually locate the <gazebo> tags reference at the very top of the document inside the <robot> tag. There no reason to think the position of the tags are important but you can try to change the declaration position of each <gazebo> element to see if something changes.

Aprt from that, maybe is a good idea to port your description to Xacro, since as I see your code you have a lot of ...(more)

Weasfas gravatar image Weasfas  ( 2020-06-20 13:12:59 -0500 )edit

I was thinking that since I saved the model's SDF within gazebo, that was the SDF converted from the URDF. Alas, I followed your translation command and none of the parameters translate to the new model.sdf.

JoshuaElliott gravatar image JoshuaElliott  ( 2020-06-20 18:35:57 -0500 )edit

But that is weird, if you use for instance the Xacro of the tutorial, the contact coefficient from <gazebo> tags do parse correctly.

The general approach if you are going to use ROS with Gazebo is using Xacro and then spawn the SDF in a gazebo world by launching the proper parser and spawner. The problem is that, I do not know why your URDF are not parse properly since I was not able to detect any errors. Maybe you can try the same questio on Gazebo answers.

Weasfas gravatar image Weasfas  ( 2020-06-21 04:48:03 -0500 )edit

Interesting, will consider posting there. Thank you for your help! I am new to all this so haven't started with Xacro yet but will soon as I'll be attempting to simulate much more complex vehicles without building the URDFs entirely by hand.

JoshuaElliott gravatar image JoshuaElliott  ( 2020-06-21 07:57:21 -0500 )edit

it seems I have the same problem. Did you find the cause or did you reformulate the whole thing in plain xacro?

moooeeeep gravatar image moooeeeep  ( 2020-11-06 04:49:24 -0500 )edit

Everything is in XACRO now and the problem has disappeared for one reason or another.

I am now able to set mu, mu2, fdir1 for each link but gave up trying to set kp and kd, I instead set those for the surface the link will contact.

JoshuaElliott gravatar image JoshuaElliott  ( 2020-11-06 22:24:33 -0500 )edit