UR10 Calibration.conf DH model generation

Hi all,
I am attempting to build a URDF for the UR10 that can be automatically generated using DH parameters.
What I currently do is read urcontrol.conf.UR10 and apply calibration.conf to them as follows:

corrected_a = delta_a (calibration.conf) + a (urcontrol.conf.UR10)
corrected_d = delta_d (calibration.conf) + d (urcontrol.conf.UR10)
corrected_alpha = delta_alpha (calibration.conf) + alpha (urcontrol.conf.UR10)
corrected_theta = delta_theta (calibration.conf)

I then use the corrected values to build my DH model. This works correctly if my values from calibration.conf are 0, but as soon as I use real robot values the transformation from ur_base to ee_link does not match the ee_link / tcp position readout on the UR simulator.

So my question is, how does the UR internally perform it’s IK using the calibration.conf to calculate its TCP position. Are all the values used? Are some omitted?

Note: My DH model is structured the same as the one posted on this page:
https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/actual-center-of-mass-for-robot-17264/

A follow up question on the same topic, what specifically is delta_theta in calibration.conf. Is it the 'angle about previous Z axis from old X to new X" as in a normal DH model?

And another question on the same problem. Within urcontrol.conf.UR10 there is also q_home_offset. What does this represent / get used for?

Hi,
Adding DH calibration coefficients to urcontrol coefficients is the right way to go, and all values are used. Either robot is not using calibration file (wrong place, wrong format, wrong name, etc…) or your calculations are wrong.
delta_theta is an offset from joint “zero” position, to true zero for achieving repeatable home position.
q_home_offset is home position error magnitude in joint space. Home position - q_home_offset = [0, 0, 0, 0, 0, 0]

For anyone in the future going down this path, the final approach I used which worked was to add the coefficients together, giving a set of a, d, theta and alpha which were the sum of the calibration.conf and urcontrol files.
To use these with your system they need to be applied in order as specified by the unmodified DH model on wiki. So the final tansform from link to link will be:
https://wikimedia.org/api/rest_v1/media/math/render/svg/70a95f9836e5efbe052491c0d73a1a76d729bc4d

In ROS tranformations are applied in XYZ R_x R_Y R_Z order so you cannot just feed the raw offset DH parameters into the joint definition in a URDF. First compute the final combined transform as follows:

https://wikimedia.org/api/rest_v1/media/math/render/svg/6963d0c47a3a894ff0719c8df348d188b996074e

Once computed the resulting matrix elements represent the individual parameters that can go directly into the URDF.

3 Likes

Hi following his topics.
Which are the units in the calibration.conf file. Because I see that in the urcontrol.conf.Ur10 the denabit hatemberrs are in meters and radians.

However taking a look at the my calibration file which has these values

delta_theta = [ -9.40498298408416866e-06, 0.27068412154354593, -0.314903939784922426, 0.0442527515792477608, 9.34172007197231709e-06, 5.93755160400425455e-05]
delta_a = [ 4.68164294735672648e-05, 0.0220582008711670552, 0.00158057850161708036, -0.00035922185146348458, 0.000281769745099834986, 0]
delta_d = [ 0.000316664403174682363, 91.8991379508659634, -90.4485183223671356, -1.45123705292539418, -0.000375134660503345652, -0.000216232948727732022]
delta_alpha = [ 0.00031730707235522182, 0.0017812786528813092, -0.0174204031901766219, -0.00145566498545623979, -8.42411731953873755e-05, 0]

is imposible that delta_d is in m since it has values around 90, an also delta_theta in radians it seems to me that has very large values 0.3 radians is like 20Âş which I think is two much. So I understand the for delta_d and delta_a units are mm and for delta_alpha and delta_theta are degrees. Is that correct?

It’s meters and radians. The large values are actually correct, since they cancel each other out in practice. But I agree, they do look weird :slight_smile:

1 Like

ok, I see. Thank you very much :smiley: !!

Hello @mojer, were you able to correctly use the DH-parameter deltas?
I am getting similar values and most of them are either very small or cancel each other, however, delta_a[1] (which is around 22mm in your case: 0.0220582…) does not cancel out and causes a corresponding offset in the final position in my case.
Did this work for you or did you have problems with this as well?
See here for my topic on this problem: Robot Calibration DH-Parameters mismatch