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

Revision history [back]

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.