Direct Kinematic model - DH parameters

Hello all,

I read the topic https://forum.universal-robots.com/t/ur10-calibration-conf-dh-model-generation/1638 but I think I miss something.

We are using offline programming softwares (Robodk & Vrep) and it would be nice if the kinematic model could be the same as the real robot (controller). So the points learnt on the robots and the simulation would be exactly the same, no discrepancy.

We build a kinematic model with Matlab Robotic Toolbox to create the DH parameters table

We don’t understand why there is this difference. What do i omit ?

Is the calibration of Universal robots done only on the dh geometric parameters (alpha, a, theta, d) ?
If it is not the case it could explain a part of the explanation ( rigidity model of the joints, gravity compensation….)

Thank you

I am not sure on the discrepancies on the values, I’d have to let one of my colleagues that has more insight on the back end of the UR calibration process answer that question.

How did you get your initial a,d, alpha and theta vales? I have done a brief analysis in the past and received a little different result. Using the following model:

image

I am be off just curious, if this could be a source of error.

Another thing to note, the values you have hihglighted on PolyScope are scaled when it comes to RX RY and RZ.

Attached/below is a Python program that exemplifies the scaling. When run it produces the following results:
PolyScope SCALED value: [0.0012193680503253582, -3.166495598686568, -0.03951768623096099]
PolyScope SCALED value: [2.4759166894662425, -5.364486160510192, 1.6506111263108283]

The first vector is the default startup position when the URControl is simulated. Note, the input and scaled vector are pretty similar, but not the same.
The second vector is based on the customer’s data.

from math import *

v_init=[-0.0012, 3.1162, 0.03889]
v=[-0.06, 0.13, -0.04]
def length(v):
return sqrt(pow(v[0],2)+pow(v[1],2)+pow(v[2],2))

def norm(v):
l=length(v)
norm=[v[0]/l, v[1]/l, v[2]/l]
return norm

def _polyscope(x,y,z):
if ( (abs(x) >= 0.001 and x < 0.0) or (abs(x) < 0.001 and abs(y) >= 0.001 and y < 0.0) or (abs(x) < 0.001 and abs(y) < 0.001 and z < 0.0) ):
scale = 1 - 2pi / length([x,y,z])
ret = [scale
x, scaley, scalez]
print "PolyScope SCALED value: ", ret
return ret
else:
ret = [x,y,z]
print "PolyScope value: ", ret
return ret

def polyscope(v):
return _polyscope(v[0], v[1], v[2])
polyscope(v_init)
polyscope(v)

I took the values directly in files stored on the real robot :

  • urcontrol.conf.UR10 pour a, d, alpha, theta
  • calibration.conf for a_delta, d_delta, alpha_delta, theta_delta

For the DH values, information stored in the urcontrol.conf.UR10 are the same as https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/
Without delta my model is OK. It’s when I add the correction values ( calibration.conf) file to the DH values, here is the bug. any idea ?

For the scaling, where do the values at the right of the arrows come from ?

The numbers on the right are the TCP values pulled through a client interface to an external source for viewing. It is just illustrating that the raw data pulled from the system is different then the displayed values on PolyScope.

This may account for the rotational differences but there seems to be some differences in your x,y and z as well. Not sure where these can be from.

Thanks for the informations of this gap !

I droped the matlab library (robotics-toolbox) and i used a python one integrated in the RoboDK Software (robodk.py).
With this new library it works fine !

I found the same result as the information of the post : calibration-conf-dh-model-generation/1638

Some pictures :

The calibration done in UR Factory seems to be only geometric.
They determines by calibration the best dh parameters to get the best accuracy in the robot volume.
No temperature correction, no joint stiffness, fixed DH…

2 Likes

Hi Inu,

We are trying to find a way to automatically load specific UR kinematics in RoboDK so that kinematics in the simulator perfectly match the real UR kinematics. We experimentally noticed that factory calibrations can deviate from 2 mm to 10 mm from the nominal model (the ones listed here).

Taking a look at an uncompressed URP file we can see the attached information related to the DH parameters at the top of the XML text (deltaTheta, a, d, alpha).

My questions are:

  1. Can we assume these parameters are the final parameters used by the UR controller (Mr. Monbrun’s kinematics calculations)?
  2. Can these parameters change without calibrating a UR robot?
  3. Is this information available in all URP files generated by a real controller?

Albert

(XML text was not displaying properly so I had to reformat the XML file to display the contents)

kinematics status="LINEARIZED" validChecksum="true"
deltaTheta value="-3.877670122826194E-7, 0.6494978343653273, -0.5944917478060878, -0.05482158380176408, -4.689045752794819E-5, 4.974990233585158E-5"
a value="2.386254745319083E-5, -0.48789028510539634, -0.5706350472740931, 2.401876047201759E-5, -5.152560163742522E-5, 0.0"
d value="0.1277171288760476, -282.49751125276725, 278.98388751352206, 3.677085553209812, 0.11558726589218675, 0.09211951577596628"
alpha value="1.5713787275265323, -0.001311355859264375, -0.008906413979055934, 1.5696536929432154, -1.5713012077564075, 0.0"
jointChecksum value="-1235180143, 1773244804, 929101865, 282395204, -269614466, 2043996791"

@florent.monbrun Great to hear! I’ll make a note of that, I wasn’t aware on the calibration details, thanks for sharing your solution!

Hello @anubiola,

Regarding your questions:

  1. Yes, the values that are provided on the link you referenced will vary per robot. The values on the uncompressed URP file will be unique per robot, due to differences that may be encountered from manufacturing and assembly of the sub-components of the system.
  2. Correct, these values should not change unless the robot is re-calibrated, or the calibration data is wiped from the controller.
  3. That I’m not sure, it should be if it was in this file you copied. There are calibration files stored on the system that should hold this data as well. urcontrol.conf is the name of the file I believe.
1 Like

I checked on my robot the dh parameters stored in one URP file :
URP%20file

The values are exactly the same as those I calculated in my test = urcontrol.conf + calibration.conf
python%20output

2 Likes

Hi, it’s been a while since this topic was posted, but I got stuck on the same problems and I think that maybe sharing my solution can be useful to other people trying to compute direct kinematics using the calibrated DH parameters.

As @florent.monbrun, I’m using the Matlab Robotic Toolbox.

I was summing delta_theta, delta_alpha, delta_d and delta_a (from calibration.conf) to the corresponding parameters theta, alpha, d and a (from https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/) for each Link object instantiated in Matlab. In this way the forward kinematic results were wrong.

The problem is that theta is the variable for a revolute joint, so its value in the instantiation of the link object should be left to 0. The value of delta_theta should be summed to the offset parameter of the link. Setting an array of offsets is equivalent to perform fkine(joints+offset). It’s a perturbation on the input joint values (which are actually theta values for revolute joints) of the forward kinematics call.

In general, even if someone is not using this particular toolbox:

  • new_a = a + delta_a

  • new_alpha = alpha + delta_alpha

  • new_d = d + delta_d

  • given the joint values j, compute the tcp pose as fkine(j+delta_theta). Using the Matlab Robotic Toolbox this can be done by setting offset=delta_theta and computing the tcp pose as fkine(j) .

In this way I got the correct forward kinematics