-
Notifications
You must be signed in to change notification settings - Fork 1k
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
How to add calibration.conf data from controller to URDF for maximum accuracy #357
Comments
Adding the deltas to the values in the urdf won't work, as you've experienced, as all those values are in metres and some of the offsets in the This topic has come up during a discussion we've had with UR, about exactly this topic. Currently, the values from the
2 to 3mm difference between the two frames is actually quite good. I've seen differences up to 15mm (but that was with high loads and fast motions). |
So you can't give any hinds how to use them at the moment? |
I've sent an email to my contacts to get some first hand information. If you need an answer right now, I wouldn't have anything for you. But if you can wait, we might. |
I can wait, thank you very much! |
Your main challenge is that you are trying to use the Denavit–Hartenberg (DH) parameters as 6D poses with 6 degrees of freedom (DOF), but DH only specifies 4 DOF. The DH notation is a complete but singular notation. Singularities occur when a rotation axis is parallel to its parent axis. This is also the reason for the large numbers in the calibration file. So the task for you is to find a strategy to estimate 6 DOF using the 4 DOF DH has. Suggestion: Note: |
Hi, I'm currently facing the same issues regarding the units of the data in calibration.conf. Has any progress been made in this direction? |
I have tried the suggestion @urrsk. Below is a sample of urdf for calculating the joints from dh parameters. Without the calibration applied, the ee_link pose is the same as the original ur3.urdf.xacro file. When applying the calibration, tool0 link is within range for Y and Z (compared to tool0_controller). But for X there is a large offset of 11.7 meters. The DH convention used is the same as the ur3.urd.xacro file. The pose of the robot is HOME (vertically up). When moving the joints in URSim, the offset from tool0 to tool0_controller is kept, except for the elbow joint. (To better visualize the joints in RViz, I divide d2, d3 and d4 from the calibration by 100) Before digging deeper, I have a couple of questions @urrsk :
ur3_calibration.urdf.xacro<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<!--
Author: Felix Messmer
-->
<xacro:include filename="$(find ur_description)/urdf/ur.transmission.xacro" />
<xacro:include filename="$(find ur_description)/urdf/ur.gazebo.xacro" />
<xacro:macro name="cylinder_inertial" params="radius length mass *origin">
<inertial>
<mass value="${mass}" />
<xacro:insert_block name="origin" />
<inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
iyy="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
izz="${0.5 * mass * radius * radius}" />
</inertial>
</xacro:macro>
<xacro:macro name="ur3_robot" params="prefix joint_limited
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
wrist_1_lower_limit:=${-pi} wrist_1_upper_limit:=${pi}
wrist_2_lower_limit:=${-pi} wrist_2_upper_limit:=${pi}
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}
offset_a1:=0.0000205594635957679934
offset_a2:=0.00150870902372793325
offset_a3:=0.000793751111829499312
offset_a4:=-0.0000193228507075169079
offset_a5:=0.0000173718501728632923
offset_a6:=0
offset_d1:=0.0000135963461434518429
offset_d2:=-110.351573314082572
offset_d3:=123.970336119564919
offset_d4:=-13.6188398018855246
offset_d5:=0.0000190738707296911336
offset_d6:=0.000477070250318664679
offset_alpha1:=0.0000466705391628519095
offset_alpha2:=0.000243411282863556191
offset_alpha3:=0.00131412175387093889
offset_alpha4:=0.000546787660626213423
offset_alpha5:=-0.000984232803121987132
offset_alpha6:=0
offset_theta1:=0.0000278890969334113371
offset_theta2:=-0.110482141198915154
offset_theta3:=0.194449868933029041
offset_theta4:=-0.0840284967969967267
offset_theta5:=0.0000609090612742423896
offset_theta6:=-0.00000396900258592857595">
<!--
offset_a1:=0
offset_a2:=0
offset_a3:=0
offset_a4:=0
offset_a5:=0
offset_a6:=0
offset_d1:=0
offset_d2:=0
offset_d3:=0
offset_d4:=0
offset_d5:=0
offset_d6:=0
offset_alpha1:=0
offset_alpha2:=0
offset_alpha3:=0
offset_alpha4:=0
offset_alpha5:=0
offset_alpha6:=0
offset_theta1:=0
offset_theta2:=0
offset_theta3:=0
offset_theta4:=0
offset_theta5:=0
offset_theta6:=0">
-->
<!-- Inertia parameters -->
<xacro:property name="base_mass" value="2.0" /> <!-- This mass might be incorrect -->
<xacro:property name="shoulder_mass" value="2.0" />
<xacro:property name="upper_arm_mass" value="3.42" />
<xacro:property name="forearm_mass" value="1.26" />
<xacro:property name="wrist_1_mass" value="0.8" />
<xacro:property name="wrist_2_mass" value="0.8" />
<xacro:property name="wrist_3_mass" value="0.35" />
<!-- These parameters are borrowed from the urcontrol.conf file
but are not verified for the correct permutation.
The permutation was guessed by looking at the UR5 parameters.
Serious use of these parameters needs further inspection. -->
<xacro:property name="shoulder_cog" value="0.0 -0.02 0.0" />
<xacro:property name="upper_arm_cog" value="0.13 0.0 0.1157" />
<xacro:property name="forearm_cog" value="0.05 0.0 0.0238" />
<xacro:property name="wrist_1_cog" value="0.0 0.0 0.01" />
<xacro:property name="wrist_2_cog" value="0.0 0.0 0.01" />
<xacro:property name="wrist_3_cog" value="0.0 0.0 -0.02" />
<!-- Kinematic model -->
<!-- Properties from urcontrol.conf -->
<xacro:property name="a1" value="${0.0 + offset_a1}" />
<xacro:property name="a2" value="${-0.24365 + offset_a2}" />
<xacro:property name="a3" value="${-0.21325 + offset_a3}" />
<xacro:property name="a4" value="${0.0 + offset_a4}" />
<xacro:property name="a5" value="${0.0 + offset_a5}" />
<xacro:property name="a6" value="${0.0 + offset_a6}" />
<xacro:property name="d1" value="${0.1519 + offset_d1}" />
<xacro:property name="d2" value="${0.0 + offset_d2}" />
<xacro:property name="d3" value="${0.0 + offset_d3}" />
<xacro:property name="d4" value="${0.11235 + offset_d4}" />
<xacro:property name="d5" value="${0.08535 + offset_d5}" />
<xacro:property name="d6" value="${0.0819 + offset_d6}" />
<xacro:property name="alpha1" value="${(pi / 2) + offset_alpha1}" />
<xacro:property name="alpha2" value="${0.0 + offset_alpha2}" />
<xacro:property name="alpha3" value="${0.0 + offset_alpha3}" />
<xacro:property name="alpha4" value="${(pi / 2) + offset_alpha4}" />
<xacro:property name="alpha5" value="${-(pi / 2) + offset_alpha5}" />
<xacro:property name="alpha6" value="${0.0 + offset_alpha6}" />
<xacro:property name="theta1" value="${0.0 + offset_theta1}" />
<xacro:property name="theta2" value="${0.0 + offset_theta2}" />
<xacro:property name="theta3" value="${0.0 + offset_theta3}" />
<xacro:property name="theta4" value="${0.0 + offset_theta4}" />
<xacro:property name="theta5" value="${0.0 + offset_theta5}" />
<xacro:property name="theta6" value="${0.0 + offset_theta6}" />
<!-- Calibration only file -->
<!--
<xacro:property name="a1" value="${ offset_a1}" />
<xacro:property name="a2" value="${ offset_a2}" />
<xacro:property name="a3" value="${ offset_a3}" />
<xacro:property name="a4" value="${ offset_a4}" />
<xacro:property name="a5" value="${ offset_a5}" />
<xacro:property name="a6" value="${ offset_a6}" />
<xacro:property name="d1" value="${ offset_d1}" />
<xacro:property name="d2" value="${ offset_d2}" />
<xacro:property name="d3" value="${ offset_d3}" />
<xacro:property name="d4" value="${ offset_d4}" />
<xacro:property name="d5" value="${ offset_d5}" />
<xacro:property name="d6" value="${ offset_d6}" />
<xacro:property name="alpha1" value="${ offset_alpha1}" />
<xacro:property name="alpha2" value="${ offset_alpha2}" />
<xacro:property name="alpha3" value="${ offset_alpha3}" />
<xacro:property name="alpha4" value="${ offset_alpha4}" />
<xacro:property name="alpha5" value="${ offset_alpha5}" />
<xacro:property name="alpha6" value="${ offset_alpha6}" />
<xacro:property name="theta1" value="${ offset_theta1}" />
<xacro:property name="theta2" value="${ offset_theta2}" />
<xacro:property name="theta3" value="${ offset_theta3}" />
<xacro:property name="theta4" value="${ offset_theta4}" />
<xacro:property name="theta5" value="${ offset_theta5}" />
<xacro:property name="theta6" value="${ offset_theta6}" />
-->
<!-- Rotation matrix (https://robotics.stackexchange.com/a/8517) -->
<xacro:property name="R1_11" value="${cos(theta1)}" />
<xacro:property name="R1_12" value="${-sin(theta1) * cos(alpha1)}" />
<xacro:property name="R1_13" value="${sin(theta1) * sin(alpha1)}" />
<xacro:property name="R1_21" value="${sin(theta1)}" />
<xacro:property name="R1_22" value="${cos(theta1) * cos(alpha1)}" />
<xacro:property name="R1_23" value="${-cos(theta1) * sin(alpha1)}" />
<xacro:property name="R1_31" value="0.0" />
<xacro:property name="R1_32" value="${sin(alpha1)}" />
<xacro:property name="R1_33" value="${cos(alpha1)}" />
<xacro:property name="R2_11" value="${cos(theta2)}" />
<xacro:property name="R2_12" value="${-sin(theta2) * cos(alpha2)}" />
<xacro:property name="R2_13" value="${sin(theta2) * sin(alpha2)}" />
<xacro:property name="R2_21" value="${sin(theta2)}" />
<xacro:property name="R2_22" value="${cos(theta2) * cos(alpha2)}" />
<xacro:property name="R2_23" value="${-cos(theta2) * sin(alpha2)}" />
<xacro:property name="R2_31" value="0.0" />
<xacro:property name="R2_32" value="${sin(alpha2)}" />
<xacro:property name="R2_33" value="${cos(alpha2)}" />
<xacro:property name="R3_11" value="${cos(theta3)}" />
<xacro:property name="R3_12" value="${-sin(theta3) * cos(alpha3)}" />
<xacro:property name="R3_13" value="${sin(theta3) * sin(alpha3)}" />
<xacro:property name="R3_21" value="${sin(theta3)}" />
<xacro:property name="R3_22" value="${cos(theta3) * cos(alpha3)}" />
<xacro:property name="R3_23" value="${-cos(theta3) * sin(alpha3)}" />
<xacro:property name="R3_31" value="0.0" />
<xacro:property name="R3_32" value="${sin(alpha3)}" />
<xacro:property name="R3_33" value="${cos(alpha3)}" />
<xacro:property name="R4_11" value="${cos(theta4)}" />
<xacro:property name="R4_12" value="${-sin(theta4) * cos(alpha4)}" />
<xacro:property name="R4_13" value="${sin(theta4) * sin(alpha4)}" />
<xacro:property name="R4_21" value="${sin(theta4)}" />
<xacro:property name="R4_22" value="${cos(theta4) * cos(alpha4)}" />
<xacro:property name="R4_23" value="${-cos(theta4) * sin(alpha4)}" />
<xacro:property name="R4_31" value="0.0" />
<xacro:property name="R4_32" value="${sin(alpha4)}" />
<xacro:property name="R4_33" value="${cos(alpha4)}" />
<xacro:property name="R5_11" value="${cos(theta5)}" />
<xacro:property name="R5_12" value="${-sin(theta5) * cos(alpha5)}" />
<xacro:property name="R5_13" value="${sin(theta5) * sin(alpha5)}" />
<xacro:property name="R5_21" value="${sin(theta5)}" />
<xacro:property name="R5_22" value="${cos(theta5) * cos(alpha5)}" />
<xacro:property name="R5_23" value="${-cos(theta5) * sin(alpha5)}" />
<xacro:property name="R5_31" value="0.0" />
<xacro:property name="R5_32" value="${sin(alpha5)}" />
<xacro:property name="R5_33" value="${cos(alpha5)}" />
<xacro:property name="R6_11" value="${cos(theta6)}" />
<xacro:property name="R6_12" value="${-sin(theta6) * cos(alpha6)}" />
<xacro:property name="R6_13" value="${sin(theta6) * sin(alpha6)}" />
<xacro:property name="R6_21" value="${sin(theta6)}" />
<xacro:property name="R6_22" value="${cos(theta6) * cos(alpha6)}" />
<xacro:property name="R6_23" value="${-cos(theta6) * sin(alpha6)}" />
<xacro:property name="R6_31" value="0.0" />
<xacro:property name="R6_32" value="${sin(alpha6)}" />
<xacro:property name="R6_33" value="${cos(alpha6)}" />
<!-- Calculate RPY for each joint -->
<xacro:property name="r1" value="${atan2(R1_33, R1_32)}" />
<xacro:property name="p1" value="${atan2(sqrt((R1_32 * R1_32) + (R1_33 * R1_33)), -R1_31)}" />
<xacro:property name="yaw1" value="${atan2(R1_11, R1_21)}" />
<xacro:property name="r2" value="${atan2(R2_33, R2_32)}" />
<xacro:property name="p2" value="${atan2(sqrt((R2_32 * R2_32) + (R2_33 * R2_33)), -R2_31)}" />
<xacro:property name="yaw2" value="${atan2(R2_11, R2_21)}" />
<xacro:property name="r3" value="${atan2(R3_33, R3_32)}" />
<xacro:property name="p3" value="${atan2(sqrt((R3_32 * R3_32) + (R3_33 * R3_33)), -R3_31)}" />
<xacro:property name="yaw3" value="${atan2(R3_11, R3_21)}" />
<xacro:property name="r4" value="${atan2(R4_33, R4_32)}" />
<xacro:property name="p4" value="${atan2(sqrt((R4_32 * R4_32) + (R4_33 * R4_33)), -R4_31)}" />
<xacro:property name="yaw4" value="${atan2(R4_11, R4_21)}" />
<xacro:property name="r5" value="${atan2(R5_33, R5_32)}" />
<xacro:property name="p5" value="${atan2(sqrt((R5_32 * R5_32) + (R5_33 * R5_33)), -R5_31)}" />
<xacro:property name="yaw5" value="${atan2(R5_11, R5_21)}" />
<xacro:property name="r6" value="${atan2(R6_33, R6_32)}" />
<xacro:property name="p6" value="${atan2(sqrt((R6_32 * R6_32) + (R6_33 * R6_33)), -R6_31)}" />
<xacro:property name="yaw6" value="${atan2(R6_11, R6_21)}" />
<!-- Calculate Transilation matrix for each joints (https://en.wikipedia.org/wiki/Denavit%E2%80%93Hartenberg_parameters) -->
<xacro:property name="x1" value="${a1 * cos(theta1)}" />
<xacro:property name="y1" value="${a1 * sin(theta1)}" />
<xacro:property name="z1" value="${d1}" />
<xacro:property name="x2" value="${a2 * cos(theta2)}" />
<xacro:property name="y2" value="${a2 * sin(theta2)}" />
<xacro:property name="z2" value="${d2}" />
<xacro:property name="x3" value="${a3 * cos(theta3)}" />
<xacro:property name="y3" value="${a3 * sin(theta3)}" />
<xacro:property name="z3" value="${d3}" />
<xacro:property name="x4" value="${a4 * cos(theta4)}" />
<xacro:property name="y4" value="${a4 * sin(theta4)}" />
<xacro:property name="z4" value="${d4}" />
<xacro:property name="x5" value="${a5 * cos(theta5)}" />
<xacro:property name="y5" value="${a5 * sin(theta5)}" />
<xacro:property name="z5" value="${d5}" />
<xacro:property name="x6" value="${a6 * cos(theta6)}" />
<xacro:property name="y6" value="${a6 * sin(theta6)}" />
<xacro:property name="z6" value="${d6}" />
<!-- Arbitrary offsets for shoulder/elbow joints -->
<!--
<xacro:property name="shoulder_offset" value="0.1198" />
<xacro:property name="elbow_offset" value="-0.0925" />
-->
<!-- Does the the calibration files include this information? -->
<xacro:property name="shoulder_offset" value="0.0" />
<xacro:property name="elbow_offset" value="0.0" />
<!-- link lengths used in model -->
<xacro:property name="shoulder_height" value="${d1}" />
<xacro:property name="upper_arm_length" value="${-a2}" />
<xacro:property name="forearm_length" value="${-a3}" />
<xacro:property name="wrist_1_length" value="${d4 - elbow_offset - shoulder_offset}" />
<xacro:property name="wrist_2_length" value="${d5}" />
<xacro:property name="wrist_3_length" value="${d6}" />
<link name="${prefix}base_link" >
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/visual/base.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/collision/base.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="0.038" mass="${base_mass}">
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link" />
<child link = "${prefix}shoulder_link" />
<origin xyz="${x1} ${y1} ${z1}" rpy="${r1} ${p1 - (pi/2)} ${yaw1 -pi/2}" />
<axis xyz="0 0 1" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="2.16"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${shoulder_pan_lower_limit}" upper="${shoulder_pan_upper_limit}" effort="330.0" velocity="2.16"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="${prefix}shoulder_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/visual/shoulder.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/collision/shoulder.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="0.178" mass="${shoulder_mass}">
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<joint name="${prefix}shoulder_lift_joint" type="revolute">
<parent link="${prefix}shoulder_link" />
<child link = "${prefix}upper_arm_link" />
<origin xyz="0 ${shoulder_offset} 0" rpy="0 ${pi/2} 0" />
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="2.16"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${shoulder_lift_lower_limit}" upper="${shoulder_lift_upper_limit}" effort="330.0" velocity="2.16"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="${prefix}upper_arm_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/visual/upperarm.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/collision/upperarm.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="${-a2}" mass="${upper_arm_mass}">
<origin xyz="0.0 0.0 ${-a2/2.0}" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<joint name="${prefix}elbow_joint" type="revolute">
<parent link="${prefix}upper_arm_link" />
<child link = "${prefix}forearm_link" />
<origin xyz="${z2} ${elbow_offset + y2} ${-x2}" rpy="${r2+pi/2} ${p2+pi/2} ${yaw2+pi/2}" />
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${elbow_joint_lower_limit}" upper="${elbow_joint_upper_limit}" effort="150.0" velocity="3.15"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="${prefix}forearm_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/visual/forearm.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/collision/forearm.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="${-a3}" mass="${forearm_mass}">
<origin xyz="0.0 0.0 ${-a3/2.0}" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<joint name="${prefix}wrist_1_joint" type="revolute">
<parent link="${prefix}forearm_link" />
<child link = "${prefix}wrist_1_link" />
<origin xyz="${z3} ${y3} ${-x3}" rpy="${r3} ${p3} ${yaw3}" />
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_1_lower_limit}" upper="${wrist_1_upper_limit}" effort="54.0" velocity="3.2"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="${prefix}wrist_1_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/visual/wrist1.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/collision/wrist1.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="0.12" mass="${wrist_1_mass}">
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<joint name="${prefix}wrist_2_joint" type="revolute">
<parent link="${prefix}wrist_1_link" />
<child link = "${prefix}wrist_2_link" />
<origin xyz="${x4} ${z4 - elbow_offset - shoulder_offset} ${y4}" rpy="${r4+pi} ${p4+pi/2} ${yaw4+pi/2}" />
<axis xyz="0 0 1" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_2_lower_limit}" upper="${wrist_2_upper_limit}" effort="54.0" velocity="3.2"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="${prefix}wrist_2_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/visual/wrist2.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/collision/wrist2.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="0.12" mass="${wrist_2_mass}">
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<joint name="${prefix}wrist_3_joint" type="revolute">
<parent link="${prefix}wrist_2_link" />
<child link = "${prefix}wrist_3_link" />
<origin xyz="${x5} ${y5} ${z5}" rpy="${r5-pi} ${p5-pi/2} ${yaw5-pi/2}" />
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}" effort="54.0" velocity="3.2"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="${prefix}wrist_3_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/visual/wrist3.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur3/collision/wrist3.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="0.12" mass="${wrist_3_mass}">
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<joint name="${prefix}ee_fixed_joint" type="fixed">
<parent link="${prefix}wrist_3_link" />
<child link = "${prefix}ee_link" />
<origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 ${pi/2.0}" />
</joint>
<link name="${prefix}ee_link">
<collision>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.01 0 0"/>
</collision>
</link>
<xacro:ur_arm_transmission prefix="${prefix}" />
<xacro:ur_arm_gazebo prefix="${prefix}" />
<!-- ROS base_link to UR 'Base' Coordinates transform -->
<link name="${prefix}base"/>
<joint name="${prefix}base_link-base_fixed_joint" type="fixed">
<!-- NOTE: this rotation is only needed as long as base_link itself is
not corrected wrt the real robot (ie: rotated over 180
degrees)
-->
<origin xyz="0 0 0" rpy="0 0 ${-pi}"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>
<!-- Frame coincident with all-zeros TCP on UR controller -->
<link name="${prefix}tool0"/>
<joint name="${prefix}wrist_3_link-tool0_fixed_joint" type="fixed">
<origin xyz="${x6} ${z6} ${y6}" rpy="${r6-pi} ${p6-pi/2} ${yaw6-pi/2}"/>
<parent link="${prefix}wrist_3_link"/>
<child link="${prefix}tool0"/>
</joint>
</xacro:macro>
</robot> |
Yes, the theta and alpha angles is in radians.
No. Again, the DH only represent the rotation axis in the kinematic chain. Not were the physically joint house are placed on the rotation axis. Challenge: Find a strategy to place that offset so it is aligns the geometry representing with the kinematics for e.g. the elbow joint. Suggestion: Find the point on the elbow's rotation axis where the base's rotation axis intersect.
Yes, it also follow UR's own description. If it does not, let me know!
Yes, the calibration offsets should be added to the default DH parameters.
|
I have successfully integrated the offset from my calibration file so that it aligns with the kinematic used in the urdf (validating using Matlab). I could use the newly generated position and orientation for each joint in the urdf but this tutorial does not recommand it:
Is this requirement only necessary for a revolute joint? Can I use a full transform for fixed joints? |
it's not really a requirement, but more of a suggestion. Libraries like IKFast tend to like URDFs set up that way much more than those with arbitrary nrs of rotations and translations of joints. In any case: it only applies to revolute joints. |
Please note that the work by Universal Robots announced at ROS-Industrial EU Conference '18 includes incorporating the calibration of individual robots into the URDFs/XACROs. |
I have successfully integrated the offset in the URDF file by keeping the same axis joint rotation. There are some errors between my offsets values versus the calibration file :
I think the errors comes from numerical round-off (I could compare with symbolic arithmetic to see if it's the case). But with precision error as low as nanometers, I don't think it matters... If someone could post a calibration file from a ur5 and a ur10, then I could check if my algorithm works. I validated my eef with the tool0_controller floating joint in RVIZ. I will post my script in a few days (Must do some cleanup first!). I guess it's not worth trying to automate this process if Universal Robots is going to implement it. |
Nice to hear about your results. It would seem to be in about the range that @fmauch reports over in #414.
Perhaps you could compare notes with @fmauch and post a comment in #414 to compare your approaches? |
Here is the repo that contains my algorithm. The readme explains how to add your calibration file in the URDF. I also explain how to validate your calibrated URDF in RViz so that you can compare your eef_link with tool0_controller. |
@cpt-yoshi I'm a bit confused. Can you explain where the values for lines 121 through 126 came from? |
@twhitney1126 These coordinate frames values came from the original URDF file: URX.urdf.xacro. These TF are needed to compute the new calibrated joints to be as close as possible with the joints in the original URDF so that it doesn't affect to much the visual and collision meshes. For the UR3, the frame coordinate T4_5NC_URDF is the transform from wrist_1_joint to wrist_2_joint that has a value of wrist_1_length: <xacro:property name="d4" value="0.11235" />
<xacro:property name="d5" value="0.08535" />
<xacro:property name="d6" value="0.0819" />
<!-- Arbitrary offsets for shoulder/elbow joints -->
<xacro:property name="shoulder_offset" value="0.1198" /> <!-- measured from model -->
<xacro:property name="elbow_offset" value="-0.0925" /> <!-- measured from model -->
<!-- link lengths used in model -->
<xacro:property name="shoulder_height" value="${d1}" />
<xacro:property name="upper_arm_length" value="${-a2}" />
<xacro:property name="forearm_length" value="${-a3}" />
<xacro:property name="wrist_1_length" value="${d4 - elbow_offset - shoulder_offset}" /> So the wrist_1_length value gives: 0.11235 - (-0.0925) - 0.1198 = 0.08505. The coordinate frame T5_6NC_URDF gives 0.08535. I will update (tonight) the code to reflect the names of the joints given in the URDF so that there is less ambiguity. |
The repo has been updated along with the readme. The joint names in the table now reflects the URDF naming convention. In RViz you now must compare tool0 with tool0_controller. The ee_fixed_joint respects the non-calibrated joint axe. I have added an estimation error table that compare the newly calibrated joints vs the original URDF ones. The max position error is 364 micro-meters and a max orientation angle error of 2.14 mRad. With these max errors, I don't think this will affect inertias for simulation but I haven't tested this in Gazebo. |
Pardon me, I tried the matlab formula (UR5 robot), then compare: What I did:
Any suggestions? |
I haven't tested it on a UR5 and UR10, so there might be an error in the algorithm. The parameters that you modified are all good. Can you validate that the Table 2 given by Matlab has approximatively a mean error of 1e-12 for position and 1e-09. If these values are good that means the error is somewhere in the URDF. If you give me your calibration file and your Xacro, I can help you out. |
Sorry for hooking into this discussion so late, I was away the last weeks... As @gavanderhoorn mentioned above, I'm currently developing a calibration routine for UR robots as part of the new UR RTDE driver. For this I created a c++-only calibration routine that "corrects" the elbow and wrist locations to be as close to the uncalibrated model as possible. In #414 I raised a couple of questions on how to integrate this into the description lying in this repository. As far as I can see, you (@cpt-yoshi) decided to calculate all 6 DOF for each joint and manually enter this into the calibration file. As I would like to automate this a little more, it would be good to make the xacro file parametrizable, don't you think? I currently go for a separate file containing the calibration information, which is currently a DH-like notation with 4 parameters per joint plus two extra parameters to specify the additional rotation introduced by the correction. When I have a look at both our implementations, it would be best to specify all xyz,rpy sets to the description. If I implemented that, I think it could be used with your algorithm, as well. What do you think? |
Hi @cpt-yoshi, thank you for following up. Attached: Table 2:
Table 3:
|
@cpt-yoshi I was able to write a generic C++ of this, that takes the two .conf files as inputs, parses the necessary values from each and creates a new URDF file. After implementation, I compared the UR known TCP position from the teach pendant and compared the result with what TF believed was the TCP and they were within 0.7 mm. Prior to the updated URDF, the error between the to was about 4.5 mm. NOTE: I only tested this on a UR5. NOTE: The only two inputs I couldn't make generic were the measured offsets in the URDF and the specified joint rotations. |
@aperaid I will also need your safety.conf file located in ~/.urcontrol. I can't initialize the simulated robot without it (In UR5 mode). There seems to have no errors in the files you uploaded. |
Good to hear!
The 0.7 mm mismatch seems a lot compared to what the algorithm reports. The max error calculated from a UR5 is in the range of 8.4e-11 meters... The algorithm dosen't validate the entire workspace but I would assume the error to not go below nano meters. |
When @gavanderhoorn told me that Universal Robot was planning to work on this, I decided to released what I had at that point. I would have eventually automated this step with c++/python with a parametrizable xacro file or something that generates a urdf file.
Personally, I think it's best to specify all 6 degree of freedom. But as pointed out by @gavanderhoorn, libraries like IKFast tend to like only one rotation at at time. To fix this, dummy joints would have to be added in the URDF because there are offsets in almost all rotations (r, p, y) of each joints. On a side note, I would also change the naming links/joints in the URDF to reflect with this REP. |
just to clarify: this comment was based on my experience with IKFast. It could be that things have changed or improved. It'd be worth making sure the advice is still relevant. If you can provide me with a calibrated urdf I'll see if I can run the IKFast generator on it. |
@cpt-yoshi @gavanderhoorn I have tested both the forward kinematics and inverse kinematics with the updated URDF. There still seems to be a few issues that show up... After applying the updated URDF, I published the expected pose and the actual robot pose and they never seemed to match exactly (same mm error), so I dug a little deeper. I found that ur_kinematics/src/ur_kin.cpp has hard-coded values for the UR3, 5, 10 (and assumes exactly orthogonal joints) that are created at compile time. This is why the robot never gets to the expected location. |
Solvers that do not take runtime parameters into account will obviously not benefit from the calibration improvements. FK/IK solvers that are capable of doing that are |
@gavanderhoorn The file ur3_calibration_robot.urdf.xacro located in this repo has my personnal calibration offsets. The repo also contains my personnal config files for URSim located here.
I only tested with KDL... That would also explain the inaccuracy of @aperaid. Can you confirm that you are using ur_kinematics as your kinematic solver?
I have update the Readme to add the current limitations with ur_kinematics. |
@cpt-yoshi , I am working with the UR10 and I used you algorithm to generate the modified/calibrated DH. after updating the urdf with those parameters, i am not getting the FK to match with what the controller says. Could you please run your algorithm with my calibration offsets and guide me as to what to change? thanks a lot in advance.
|
Can someone point me out to where would be the algorithm to generate the yaml supporting file? This is my calibration file the UR5 CB3 I am working with. |
The script is part of a new driver suite that is currently in a closed beta state. It will be released soon(ish), hopefully. |
Hello, In order to get an accurate model of my UR10 in simulation, I moved the robot in hundreds of positions and get the position in Cartesian and joint space. Then I used scipy to find the DH parameters that minimized the error between the cartesian position and the position from the direct geometrical model. I limited the search around the theoretical DH parameters. I have now this parameters : The error is less than 1 mm and 0.001 rads on the three rotation angles. But I don't get how to create the urdf from the DH parameters as the coordinates of the robot are not the same (position and rotation axis). Does someone know how to fix this ? |
The soon(ish) mentioned above comes closer probably being somewhere in October. |
With Therefore I'm closing this issue. Refer to the announcement on ROS Discourse. For further information on how |
Hi,
I try to implement the calibration data from the UR-controller to the URDF-File. The goal is to reduce the discrepancy between the position of tool0 in MoveIt and the tool0_controller (2-3mm).
I copied the calibration.conf data from the controller. The content of the file is:
The following properties are defined in the URDF-File from ur_description of UR5:
How can I implement the calibration data in the URDF-File? Just adding the delta values to the values from the URDF-File results in crazy numbers.
The text was updated successfully, but these errors were encountered: