ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Ball joint in URDF

asked 2017-04-01 18:22:44 -0600

PedroHRPBS gravatar image

updated 2017-04-04 18:46:49 -0600

Hello, guys

I'd like to know how do I create a 3D ball joint using URDF.

I've tried some approaches like trying to create a dummy link, but I had no success.

In my project I have a quadrotor and a ball, I'd like to fix them, so the quad could roll, pitch and yaw on a fixed spot.

Any thoughts about that?

EDIT

I'll give more explanation about my problem.

In my project I want to develop a system for drones to share payload, and I want to avoid the problem of collision keeping them fixed in distance. To achieve that, I had the idea of using a bar, where they would be able to move freely. The image above ilustrates the ideia with one quad.

https://ibb.co/efGc3v

The problem that I'm facing right now is with the spherical joint between the quad and the ball. I managed to achieve 1 DoF at the moment. I'll copy here the 3 files that I'm using to make it work.

The bar model:

<?xml version="1.0"?>

<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
    <xacro:property name="M_PI" value="3.1415926535897931"/>

    <xacro:macro name="barra_model" params="name parent *origin">
      <joint name="${name}_joint" type="fixed">
        <xacro:insert_block name="origin" />
        <parent link="${parent}"/>
        <child link="barra_baselink"/>
      </joint>

      <link name="barra_baselink">
        <visual>
          <geometry>
            <sphere radius="0.025"/>
          </geometry>
      <origin rpy="0 0 0" xyz="0.9875 0 0.1125"/>
          <material name="white">
            <color rgba="1 1 1 1"/>
          </material>
        </visual>
        <inertial>
          <mass value="0.025" />
          <origin xyz="0.9875 0 0.1125" rpy="0 0 0" />
          <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
        </inertial>
    <collision>
          <geometry>
            <sphere radius="0.025"/>
          </geometry>
      <origin rpy="0 0 0" xyz="0.9875 0 0.1125"/>
        </collision>
      </link>   

      <joint name="${name}_b2ebase_link" type="fixed">
      <parent link="barra_baselink"/>
          <child link="${name}_b2"/>
      </joint>

    <link name="${name}_b2">
        <visual>
          <geometry>
            <box size="0.025 0.025 0.10"/>
          </geometry>
      <origin rpy="0 0 0" xyz="0.9875 0 0.075"/>
        </visual>
        <inertial>
          <mass value="0.050" />
          <origin xyz="0.9875 0 0.075" rpy="0 0 0" />
          <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
        </inertial>
    <collision>
          <geometry>
            <box size="0.05 0.05 0.20"/>
          </geometry>
      <origin rpy="0 0 0" xyz="0.9875 0 0.075"/>
        </collision>
      </link>

      <joint name="${name}_b1eb2" type="fixed">
      <parent link="${name}_b2"/>
          <child link="${name}_bhor"/>
      </joint>

      <link name="${name}_bhor">
        <visual>
          <geometry>
            <box size="2.0 0.025 0.025"/>
          </geometry>
      <origin rpy="0 0 0" xyz="0 0 0.0125"/>
        </visual>
        <inertial>
          <mass value="0.253" />
          <origin xyz="0 0 0" rpy="0 0 0.0125" />
          <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
        </inertial>
    <collision>
          <geometry>
            <box size="2.0 0.025 0.025"/>
          </geometry>
      <origin rpy="0 0 0" xyz="0 ...
(more)
edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
8

answered 2017-04-11 19:05:13 -0600

RafaelGB gravatar image

updated 2017-04-11 19:06:09 -0600

The problem occurs because of two reasons:

  • Gazebo "merges" child links to their parent when they are connected via a fixed joint, creating only one link with the name of the parent link;
  • Gazebo ignores links without inertial properties

In the first case you have one link that has no inertia: "junta1". However, Gazebo merges all the links that are created by the "barra_model" macro into the "junta1" link, because they are all connected through fixed joints. Then "junta1" "gains" inertia, since the inertia objects of its child links now belong to it. Then it is not ignored.

In the second case, you have two links without inertia, "junta1" and "junta2". They are connected through a continuous joint, so Gazebo will not merge them. This lets "junta1" without inertia, and it gets ignored. Since there is no "junta1", all its children (i.e the whole bar) are not created. That's why the bar disappears.

The solution is to give a simple inertial block to the links, with a small mass. In the code below, I copied the same inertial properties from the spheres in the bar, and added the third link to create the ball joint.

<?xml version="1.0"?>

<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="junta_model" params="name parent child *origin">

  <joint name="${name}_joint" type="continuous">
    <parent link="base_link"/>
    <child link="junta1"/>
    <axis xyz="0 1 0" />
  </joint>

  <link name="junta1">
    <inertial>
      <mass value="0.025" />
      <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
    </inertial>
  </link>

  <joint name="${name}_joint2" type="continuous">
    <parent link="junta1"/>
    <child link="junta2"/>
    <axis xyz="0 0 1" />
  </joint>

  <link name="junta2">
    <inertial>
      <mass value="0.025" />
      <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
    </inertial>  
  </link>

  <joint name="${name}_joint3" type="continuous">
    <parent link="junta1"/>
    <child link="junta3"/>
    <axis xyz="1 0 0" />
  </joint>

  <link name="junta3">
    <inertial>
      <mass value="0.025" />
      <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
    </inertial>  
  </link>

<joint name="${name}_jointfixed" type="fixed">
    <xacro:insert_block name="origin" />    
    <parent link="junta3"/>
    <child link="${child}"/>
  </joint>
</xacro:macro>

</robot>

I hope it helps.

edit flag offensive delete link more

Comments

it worked! thank you very much for the explanation!

PedroHRPBS gravatar image PedroHRPBS  ( 2017-04-11 19:15:17 -0600 )edit
1

answered 2017-04-02 12:37:49 -0600

I think by "ball joint", you are talking about a single joint with 3 mutually-orthogonal rotational degrees-of-freedom -- often called a spherical joint. If this is indeed the case, in your URDF, you would need to build this joint by composing three separate joints and corresponding links of either the continuous or revolute type. Here's a small snippet copied from here as an example:

<!-- left shoulder -->
<joint name="LShoulder" type="fixed" >
    <origin xyz="0.15 0  0.043529411764705886" />
    <parent link="torso" />
    <child link="left_shoulder" />
</joint>
<link name="left_shoulder" />
<joint name="LShoulderPsi" type="continuous" >
    <parent link="left_shoulder" />
    <child link="left_shoulder_psi_link" />
    <axis xyz="0 0 1" />
    <dynamics damping="0.005" />
</joint>
<link name="left_shoulder_psi_link" />
<joint name="LShoulderTheta" type="continuous" >
    <parent link="left_shoulder_psi_link"/>
    <child link="left_shoulder_theta_link"/>
    <axis xyz="0 1 0" />
    <dynamics damping="0.005" />
</joint>
<link name="left_shoulder_theta_link" />
<joint name="LShoulderPhi" type="continuous" >
    <parent link="left_shoulder_theta_link"/>
    <child link="left_humerus"/>
    <axis xyz="1 0 0" />
    <dynamics damping="0.005" />
</joint>

In the above example, the spherical joint is described using ZYX relative-axis Euler angles.

edit flag offensive delete link more

Comments

That's exactly what I meant. But it didn't work. I have a quadrotor (link1) and a bar with a ball in one end which I want to fix in the quad base with the spherical joint. If I try to create a continuous joint between them (quad as parent and bar as child) the quad rotates relative to the center of

PedroHRPBS gravatar image PedroHRPBS  ( 2017-04-02 19:54:30 -0600 )edit

Center of the bar. If I switch roles (bar as parent and quad as child) my controller which I use to fly the quad will stop working. When I create a third link between them, I can make 1 DoF work. But for some reason, when I try to implement your suggestion, when I add the second DoF

PedroHRPBS gravatar image PedroHRPBS  ( 2017-04-02 19:56:47 -0600 )edit

Second DoF my bar disappears when I spawn the model in Gazebo. I've tried many combinations, creating more links between them, editing the bar model, but everytime I add a second DoF the bar doesn't show up in Gazebo. I can't find a way out to solve this problem.

PedroHRPBS gravatar image PedroHRPBS  ( 2017-04-02 20:19:14 -0600 )edit

I thought about migrating to SDF but then I don't know how to make the plugins work nor how to spawn the model through ROS so I can control it with my xbox controller.

PedroHRPBS gravatar image PedroHRPBS  ( 2017-04-02 20:20:43 -0600 )edit

The Gazebo/SDF stuff is far afield from your original question. If you have questions on these topics, I'd suggest opening new questions. It's difficult to understand what doesn't work and what you are trying to do. Perhaps you could edit your original question to provide more info, or ask new Q.

jarvisschultz gravatar image jarvisschultz  ( 2017-04-02 20:47:32 -0600 )edit

Hello, Jarvis, I just did what you said me to do. Thank you very much!

PedroHRPBS gravatar image PedroHRPBS  ( 2017-04-04 18:44:05 -0600 )edit
0

answered 2019-05-07 02:02:25 -0600

Angel-J gravatar image

updated 2019-05-07 02:06:56 -0600

the closed_loop_plugin can solve the issue that URDF not support Closed loop chains.

The URDF served the ROS, it has several notable shortcomings.one is it does not support closed loop chains. The SDF served the gazebo, support closed loop chains - this can be achieved by allowing two different joints to have the same child link but different parents

please refer to : http://wiki.ros.org/action/edit/Angel... or https://github.com/wojiaojiao/pegasus...

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2017-04-01 18:22:44 -0600

Seen: 6,652 times

Last updated: May 07 '19