
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.
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="<span class="math-container">${name}_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="$</span>{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="<span class="math-container">${name}_b2ebase_link" type="fixed">
<parent link="barra_baselink"/>
<child link="$</span>{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="<span class="math-container">${name}_b1eb2" type="fixed">
<parent link="$</span>{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 0 0.0125"/>
</collision>
</link>
<joint name="<span class="math-container">${name}_b1eb3" type="fixed">
<parent link="$</span>{name}_bhor"/>
<child link="${name}_b3"/>
</joint>
<link name="${name}_b3">
<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.025 0.025 0.20"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.9875 0 0.075"/>
</collision>
</link>
<joint name="<span class="math-container">${name}_b3ebase_link2" type="fixed">
<parent link="$</span>{name}_b3"/>
<child link="${name}_link2"/>
</joint>
<link name="${name}_link2">
<visual>
<geometry>
<sphere radius="0.025"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.9875 0 0.1125"/>
<material name="white"/>
</visual>
<inertial>
<mass value="0.050" />
<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>
</xacro:macro>
<xacro:macro name="barra_" params="name parent *origin">
<xacro:barra_model name="<span class="math-container">${name}" parent="$</span>{parent}">
<xacro:insert_block name="origin" />
</xacro:barra_model>
</xacro:macro>
</robot>
The link to make the 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="${parent}"/>
<child link="junta1"/>
<axis xyz="0 1 0" />
</joint>
<link name="junta1" />
<joint name="<span class="math-container">${name}_jointfixed" type="fixed">
<xacro:insert_block name="origin" />
<parent link="junta1"/>
<child link="$</span>{child}"/>
</joint>
</xacro:macro>
</robot>
The urdf with quad + link + bar:
<?xml version="1.0"?>
<robot name="quadrotor" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926535897931"/>
<xacro:include filename="$(find hector_quadrotor_description)/urdf/quadrotor_base.urdf.xacro" />
<xacro:quadrotor_base_macro />
<xacro:include filename="$(find hector_sensors_description)/urdf/juntayaw.urdf.xacro" />
<xacro:junta_model name="juntayaw" parent="base_link" child="barra_baselink">
<origin xyz="0.485 0 -0.07" rpy="0 0 0"/>
</xacro:junta_model>
<xacro:include filename="$(find hector_sensors_description)/urdf/barra.urdf.xacro" />
<xacro:barra_model name="barra" parent="junta1">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:barra_model>
</robot>
The result with Pitch angle: https://ibb.co/b1XTAa
When I try to add a second DoF, my bar disappears:
<?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="${parent}"/>
<child link="junta1"/>
<axis xyz="0 1 0" />
</joint>
<link name="junta1" />
<joint name="{name}_joint2" type="continuous">
<parent link="junta1"/>
<child link="junta2"/>
<axis xyz="0 0 1" />
</joint>
<link name="junta2" />
<joint name="<span class="math-container">${name}_jointfixed" type="fixed">
<xacro:insert_block name="origin" />
<parent link="junta2"/>
<child link="$</span>{child}"/>
</joint>
</xacro:macro>
</robot>
Another approach that I tried was to change the relation between Quad and Bar, to make the Quad as child and the Bar as parent, but then, my controller stops working and I can't fly the Quad anymore.
Please, if you need more information to understand the problem, just ask then I will try to make it more clear.
Thanks in advance
Pedro
Originally posted by PedroHRPBS on ROS Answers with karma: 13 on 2017-04-01
Post score: 0